Merge branch 'master' into patch-1
This commit is contained in:
commit
96acb74b87
29
.travis.yml
29
.travis.yml
|
@ -23,15 +23,20 @@ matrix:
|
|||
- python3
|
||||
- python3-pip
|
||||
- libboost-python-dev
|
||||
- libtiff5-dev
|
||||
- libjpeg-dev
|
||||
install:
|
||||
- pip2 install --user setuptools nose2
|
||||
- pip3 install --user setuptools nose2
|
||||
- make setup
|
||||
- pip2 install -q --user setuptools nose2
|
||||
- pip3 install -q --user setuptools nose2
|
||||
script:
|
||||
- make setup >/dev/null
|
||||
- make LibCarla >/dev/null
|
||||
- make PythonAPI >/dev/null
|
||||
- while sleep 2m; do echo "still building..."; done &
|
||||
- make setup > build.log 2>&1
|
||||
- make LibCarla > build.log 2>&1
|
||||
- make PythonAPI > build.log 2>&1
|
||||
- kill %1
|
||||
- make check ARGS="--all --gtest_args=--gtest_filter=-*_mt"
|
||||
after_failure:
|
||||
- tail --lines=2000 build.log
|
||||
|
||||
- env: TEST="Pylint 2"
|
||||
addons:
|
||||
|
@ -40,22 +45,16 @@ matrix:
|
|||
- python
|
||||
- python-pip
|
||||
install:
|
||||
- pip2 install --user -r PythonClient/requirements.txt
|
||||
- pip2 install --user pylint
|
||||
- pip2 install -q --user -r PythonClient/requirements.txt
|
||||
- pip2 install -q --user pylint
|
||||
script:
|
||||
- pylint --disable=R,C --rcfile=PythonClient/.pylintrc PythonClient/carla PythonClient/*.py
|
||||
|
||||
- env: TEST="MkDocs"
|
||||
install:
|
||||
- pip install --user mkdocs
|
||||
- pip install -q --user mkdocs
|
||||
script:
|
||||
- mkdocs build --verbose --clean --strict --site-dir _site
|
||||
|
||||
- env: TEST="AwesomeBot"
|
||||
install:
|
||||
- gem install awesome_bot
|
||||
script:
|
||||
- find . -name '*.md' | xargs awesome_bot --allow-dupe --allow-redirect --skip-save-results
|
||||
|
||||
notifications:
|
||||
email: false
|
||||
|
|
|
@ -8,7 +8,7 @@ Install the build tools and dependencies
|
|||
```
|
||||
sudo add-apt-repository ppa:ubuntu-toolchain-r/test
|
||||
sudo apt-get update
|
||||
sudo apt-get install build-essential clang-5.0 lld-5.0 g++-7 ninja-build python python-pip python-dev tzdata sed curl wget unzip autoconf libtool
|
||||
sudo apt-get install build-essential clang-5.0 lld-5.0 g++-7 ninja-build python python-pip python-dev libpng16-dev libtiff5-dev libjpeg-dev tzdata sed curl wget unzip autoconf libtool
|
||||
pip install --user setuptools nose2
|
||||
```
|
||||
|
||||
|
|
|
@ -38,8 +38,8 @@
|
|||
- `contains_attribute(key)`
|
||||
- `get_attribute(key)`
|
||||
- `set_attribute(key, value)`
|
||||
- `__len__`
|
||||
- `__iter__`
|
||||
- `__len__()`
|
||||
- `__iter__()`
|
||||
|
||||
## `carla.ActorAttribute`
|
||||
|
||||
|
@ -64,6 +64,7 @@
|
|||
|
||||
- `id`
|
||||
- `type_id`
|
||||
- `is_alive`
|
||||
- `get_world()`
|
||||
- `get_location()`
|
||||
- `get_transform()`
|
||||
|
@ -73,21 +74,41 @@
|
|||
|
||||
## `carla.Vehicle(carla.Actor)`
|
||||
|
||||
- `control`
|
||||
- `apply_control(vehicle_control)`
|
||||
- `set_autopilot(enabled=True)`
|
||||
|
||||
## `carla.Sensor(carla.Actor)`
|
||||
|
||||
- `is_listening`
|
||||
- `listen(callback_function)`
|
||||
- `stop()`
|
||||
|
||||
## `carla.Image`
|
||||
|
||||
- `frame_number`
|
||||
- `transform`
|
||||
- `width`
|
||||
- `height`
|
||||
- `type`
|
||||
- `fov`
|
||||
- `raw_data`
|
||||
- `convert(color_converter)`
|
||||
- `save_to_disk(path, color_converter=None)`
|
||||
- `__len__()`
|
||||
- `__iter__()`
|
||||
|
||||
## `carla.LidarMeasurement`
|
||||
|
||||
- `frame_number`
|
||||
- `transform`
|
||||
- `horizontal_angle`
|
||||
- `channels`
|
||||
- `raw_data`
|
||||
- `get_point_count(channel)`
|
||||
- `save_to_disk(path)`
|
||||
- `__len__()`
|
||||
- `__iter__()`
|
||||
|
||||
## `carla.VehicleControl`
|
||||
|
||||
|
@ -96,6 +117,8 @@
|
|||
- `brake`
|
||||
- `hand_brake`
|
||||
- `reverse`
|
||||
- `__eq__()`
|
||||
- `__ne__()`
|
||||
|
||||
## `carla.Location`
|
||||
|
||||
|
@ -119,3 +142,11 @@
|
|||
- `r`
|
||||
- `g`
|
||||
- `b`
|
||||
- `a`
|
||||
|
||||
## `carla.ColorConverter`
|
||||
|
||||
- `None`
|
||||
- `Depth`
|
||||
- `LogarithmicDepth`
|
||||
- `CityScapesPalette`
|
||||
|
|
|
@ -6,21 +6,128 @@ install(DIRECTORY "${RPCLIB_INCLUDE_PATH}/rpc" DESTINATION include)
|
|||
file(GLOB libcarla_carla_rpclib "${RPCLIB_LIB_PATH}/*.*")
|
||||
install(FILES ${libcarla_carla_rpclib} DESTINATION lib)
|
||||
|
||||
file(GLOB libcarla_sources
|
||||
"${libcarla_source_path}/carla/*.h"
|
||||
"${libcarla_source_path}/carla/*.cpp")
|
||||
# Install boost headers.
|
||||
|
||||
file(GLOB_RECURSE libcarla_client_sources
|
||||
"${libcarla_source_path}/carla/client/*.h"
|
||||
install(DIRECTORY "${BOOST_INCLUDE_PATH}/boost" DESTINATION include)
|
||||
|
||||
file(GLOB boost_libraries "${BOOST_LIB_PATH}/*")
|
||||
install(FILES ${boost_libraries} DESTINATION lib)
|
||||
|
||||
# Add sources.
|
||||
|
||||
file(GLOB libcarla_carla_sources
|
||||
"${libcarla_source_path}/carla/*.cpp"
|
||||
"${libcarla_source_path}/carla/*.h")
|
||||
set(libcarla_sources "${libcarla_sources};${libcarla_carla_sources}")
|
||||
install(FILES ${libcarla_carla_sources} DESTINATION include/carla)
|
||||
|
||||
file(GLOB libcarla_carla_client_sources
|
||||
"${libcarla_source_path}/carla/client/*.cpp"
|
||||
"${libcarla_source_path}/carla/rpc/*.h"
|
||||
"${libcarla_source_path}/carla/rpc/*.cpp"
|
||||
"${libcarla_source_path}/carla/streaming/*.h"
|
||||
"${libcarla_source_path}/carla/streaming/*.cpp")
|
||||
"${libcarla_source_path}/carla/client/*.h")
|
||||
set(libcarla_sources "${libcarla_sources};${libcarla_carla_client_sources}")
|
||||
install(FILES ${libcarla_carla_client_sources} DESTINATION include/carla/client)
|
||||
|
||||
file(GLOB libcarla_carla_client_detail_sources
|
||||
"${libcarla_source_path}/carla/client/detail/*.cpp"
|
||||
"${libcarla_source_path}/carla/client/detail/*.h")
|
||||
set(libcarla_sources "${libcarla_sources};${libcarla_carla_client_detail_sources}")
|
||||
install(FILES ${libcarla_carla_client_detail_sources} DESTINATION include/carla/client/detail)
|
||||
|
||||
file(GLOB libcarla_carla_geom_sources
|
||||
"${libcarla_source_path}/carla/geom/*.cpp"
|
||||
"${libcarla_source_path}/carla/geom/*.h")
|
||||
set(libcarla_sources "${libcarla_sources};${libcarla_carla_geom_sources}")
|
||||
install(FILES ${libcarla_carla_geom_sources} DESTINATION include/carla/geom)
|
||||
|
||||
file(GLOB libcarla_carla_image_sources
|
||||
"${libcarla_source_path}/carla/image/*.cpp"
|
||||
"${libcarla_source_path}/carla/image/*.h")
|
||||
set(libcarla_sources "${libcarla_sources};${libcarla_carla_image_sources}")
|
||||
install(FILES ${libcarla_carla_image_sources} DESTINATION include/carla/image)
|
||||
|
||||
file(GLOB libcarla_carla_opendrive_sources
|
||||
"${libcarla_source_path}/carla/opendrive/*.cpp"
|
||||
"${libcarla_source_path}/carla/opendrive/*.h")
|
||||
set(libcarla_sources "${libcarla_sources};${libcarla_carla_opendrive_sources}")
|
||||
install(FILES ${libcarla_carla_opendrive_sources} DESTINATION include/carla/opendrive)
|
||||
|
||||
file(GLOB libcarla_carla_pointcloud_sources
|
||||
"${libcarla_source_path}/carla/pointcloud/*.cpp"
|
||||
"${libcarla_source_path}/carla/pointcloud/*.h")
|
||||
set(libcarla_sources "${libcarla_sources};${libcarla_carla_pointcloud_sources}")
|
||||
install(FILES ${libcarla_carla_pointcloud_sources} DESTINATION include/carla/pointcloud)
|
||||
|
||||
file(GLOB libcarla_carla_profiler_sources
|
||||
"${libcarla_source_path}/carla/profiler/*.cpp"
|
||||
"${libcarla_source_path}/carla/profiler/*.h")
|
||||
set(libcarla_sources "${libcarla_sources};${libcarla_carla_profiler_sources}")
|
||||
install(FILES ${libcarla_carla_profiler_sources} DESTINATION include/carla/profiler)
|
||||
|
||||
file(GLOB libcarla_carla_road_sources
|
||||
"${libcarla_source_path}/carla/road/*.cpp"
|
||||
"${libcarla_source_path}/carla/road/*.h")
|
||||
set(libcarla_sources "${libcarla_sources};${libcarla_carla_road_sources}")
|
||||
install(FILES ${libcarla_carla_road_sources} DESTINATION include/carla/road)
|
||||
|
||||
file(GLOB libcarla_carla_rpc_sources
|
||||
"${libcarla_source_path}/carla/rpc/*.cpp"
|
||||
"${libcarla_source_path}/carla/rpc/*.h")
|
||||
set(libcarla_sources "${libcarla_sources};${libcarla_carla_rpc_sources}")
|
||||
install(FILES ${libcarla_carla_rpc_sources} DESTINATION include/carla/rpc)
|
||||
|
||||
file(GLOB libcarla_carla_sensor_sources
|
||||
"${libcarla_source_path}/carla/sensor/*.cpp"
|
||||
"${libcarla_source_path}/carla/sensor/*.h")
|
||||
set(libcarla_sources "${libcarla_sources};${libcarla_carla_sensor_sources}")
|
||||
install(FILES ${libcarla_carla_sensor_sources} DESTINATION include/carla/sensor)
|
||||
|
||||
file(GLOB libcarla_carla_sensor_data_sources
|
||||
"${libcarla_source_path}/carla/sensor/data/*.cpp"
|
||||
"${libcarla_source_path}/carla/sensor/data/*.h")
|
||||
set(libcarla_sources "${libcarla_sources};${libcarla_carla_sensor_data_sources}")
|
||||
install(FILES ${libcarla_carla_sensor_data_sources} DESTINATION include/carla/sensor/data)
|
||||
|
||||
file(GLOB libcarla_carla_sensor_s11n_sources
|
||||
"${libcarla_source_path}/carla/sensor/s11n/*.cpp"
|
||||
"${libcarla_source_path}/carla/sensor/s11n/*.h")
|
||||
set(libcarla_sources "${libcarla_sources};${libcarla_carla_sensor_s11n_sources}")
|
||||
install(FILES ${libcarla_carla_sensor_s11n_sources} DESTINATION include/carla/sensor/s11n)
|
||||
|
||||
file(GLOB libcarla_carla_streaming_sources
|
||||
"${libcarla_source_path}/carla/streaming/*.cpp"
|
||||
"${libcarla_source_path}/carla/streaming/*.h")
|
||||
set(libcarla_sources "${libcarla_sources};${libcarla_carla_streaming_sources}")
|
||||
install(FILES ${libcarla_carla_streaming_sources} DESTINATION include/carla/streaming)
|
||||
|
||||
file(GLOB libcarla_carla_streaming_detail_sources
|
||||
"${libcarla_source_path}/carla/streaming/detail/*.cpp"
|
||||
"${libcarla_source_path}/carla/streaming/detail/*.h")
|
||||
set(libcarla_sources "${libcarla_sources};${libcarla_carla_streaming_detail_sources}")
|
||||
install(FILES ${libcarla_carla_streaming_detail_sources} DESTINATION include/carla/streaming/detail)
|
||||
|
||||
file(GLOB libcarla_carla_streaming_detail_tcp_sources
|
||||
"${libcarla_source_path}/carla/streaming/detail/tcp/*.cpp"
|
||||
"${libcarla_source_path}/carla/streaming/detail/tcp/*.h")
|
||||
set(libcarla_sources "${libcarla_sources};${libcarla_carla_streaming_detail_tcp_sources}")
|
||||
install(FILES ${libcarla_carla_streaming_detail_tcp_sources} DESTINATION include/carla/streaming/detail/tcp)
|
||||
|
||||
file(GLOB libcarla_carla_streaming_low_level_sources
|
||||
"${libcarla_source_path}/carla/streaming/low_level/*.cpp"
|
||||
"${libcarla_source_path}/carla/streaming/low_level/*.h")
|
||||
set(libcarla_sources "${libcarla_sources};${libcarla_carla_streaming_low_level_sources}")
|
||||
install(FILES ${libcarla_carla_streaming_low_level_sources} DESTINATION include/carla/streaming/low_level)
|
||||
|
||||
file(GLOB libcarla_moodycamel_sources
|
||||
"${libcarla_source_path}/moodycamel/*.h")
|
||||
set(libcarla_sources "${libcarla_sources};${libcarla_moodycamel_sources}")
|
||||
install(FILES ${libcarla_moodycamel_sources} DESTINATION include/moodycamel)
|
||||
|
||||
# ==============================================================================
|
||||
# Create targets for debug and release in the same build type.
|
||||
# ==============================================================================
|
||||
|
||||
foreach(target carla_client_debug carla_client)
|
||||
add_library(${target} STATIC ${libcarla_client_sources} ${libcarla_sources})
|
||||
add_library(${target} STATIC ${libcarla_sources})
|
||||
|
||||
target_include_directories(${target} PRIVATE
|
||||
"${BOOST_INCLUDE_PATH}"
|
||||
|
@ -36,49 +143,3 @@ target_compile_definitions(carla_client_debug PUBLIC -DBOOST_ASIO_ENABLE_BUFFER_
|
|||
|
||||
# Specific options for release.
|
||||
set_target_properties(carla_client PROPERTIES COMPILE_FLAGS ${CMAKE_CXX_FLAGS_RELEASE})
|
||||
|
||||
# Install headers.
|
||||
|
||||
install(DIRECTORY "${BOOST_INCLUDE_PATH}/boost" DESTINATION include)
|
||||
|
||||
file(GLOB boost_libraries "${BOOST_LIB_PATH}/*")
|
||||
install(FILES ${boost_libraries} DESTINATION lib)
|
||||
|
||||
file(GLOB libcarla_carla_headers
|
||||
"${libcarla_source_path}/carla/*.cpp"
|
||||
"${libcarla_source_path}/carla/*.h")
|
||||
install(FILES ${libcarla_carla_headers} DESTINATION include/carla)
|
||||
|
||||
file(GLOB libcarla_moodycamel_headers
|
||||
"${libcarla_source_path}/moodycamel/*.h")
|
||||
install(FILES ${libcarla_moodycamel_headers} DESTINATION include/moodycamel)
|
||||
|
||||
file(GLOB libcarla_carla_client_headers
|
||||
"${libcarla_source_path}/carla/client/*.cpp"
|
||||
"${libcarla_source_path}/carla/client/*.h")
|
||||
install(FILES ${libcarla_carla_client_headers} DESTINATION include/carla/client)
|
||||
|
||||
file(GLOB libcarla_carla_rpc_headers
|
||||
"${libcarla_source_path}/carla/rpc/*.cpp"
|
||||
"${libcarla_source_path}/carla/rpc/*.h")
|
||||
install(FILES ${libcarla_carla_rpc_headers} DESTINATION include/carla/rpc)
|
||||
|
||||
file(GLOB libcarla_carla_streaming_headers
|
||||
"${libcarla_source_path}/carla/streaming/*.cpp"
|
||||
"${libcarla_source_path}/carla/streaming/*.h")
|
||||
install(FILES ${libcarla_carla_streaming_headers} DESTINATION include/carla/streaming)
|
||||
|
||||
file(GLOB libcarla_carla_streaming_detail_headers
|
||||
"${libcarla_source_path}/carla/streaming/detail/*.cpp"
|
||||
"${libcarla_source_path}/carla/streaming/detail/*.h")
|
||||
install(FILES ${libcarla_carla_streaming_detail_headers} DESTINATION include/carla/streaming/detail)
|
||||
|
||||
file(GLOB libcarla_carla_streaming_detail_tcp_headers
|
||||
"${libcarla_source_path}/carla/streaming/detail/tcp/*.cpp"
|
||||
"${libcarla_source_path}/carla/streaming/detail/tcp/*.h")
|
||||
install(FILES ${libcarla_carla_streaming_detail_tcp_headers} DESTINATION include/carla/streaming/detail/tcp)
|
||||
|
||||
file(GLOB libcarla_carla_streaming_low_level_headers
|
||||
"${libcarla_source_path}/carla/streaming/low_level/*.cpp"
|
||||
"${libcarla_source_path}/carla/streaming/low_level/*.h")
|
||||
install(FILES ${libcarla_carla_streaming_low_level_headers} DESTINATION include/carla/streaming/low_level)
|
||||
|
|
|
@ -17,9 +17,24 @@ install(DIRECTORY "${libcarla_source_path}/compiler" DESTINATION include)
|
|||
file(GLOB libcarla_carla_headers "${libcarla_source_path}/carla/*.h")
|
||||
install(FILES ${libcarla_carla_headers} DESTINATION include/carla)
|
||||
|
||||
file(GLOB libcarla_carla_geom_headers "${libcarla_source_path}/carla/geom/*.h")
|
||||
install(FILES ${libcarla_carla_geom_headers} DESTINATION include/carla/geom)
|
||||
|
||||
file(GLOB libcarla_carla_profiler_headers "${libcarla_source_path}/carla/profiler/*.h")
|
||||
install(FILES ${libcarla_carla_profiler_headers} DESTINATION include/carla/profiler)
|
||||
|
||||
file(GLOB libcarla_carla_rpc_headers "${libcarla_source_path}/carla/rpc/*.h")
|
||||
install(FILES ${libcarla_carla_rpc_headers} DESTINATION include/carla/rpc)
|
||||
|
||||
file(GLOB libcarla_carla_sensor_headers "${libcarla_source_path}/carla/sensor/*.h")
|
||||
install(FILES ${libcarla_carla_sensor_headers} DESTINATION include/carla/sensor)
|
||||
|
||||
file(GLOB libcarla_carla_sensor_data_headers "${libcarla_source_path}/carla/sensor/data/*.h")
|
||||
install(FILES ${libcarla_carla_sensor_data_headers} DESTINATION include/carla/sensor/data)
|
||||
|
||||
file(GLOB libcarla_carla_sensor_s11n_headers "${libcarla_source_path}/carla/sensor/s11n/*.h")
|
||||
install(FILES ${libcarla_carla_sensor_s11n_headers} DESTINATION include/carla/sensor/s11n)
|
||||
|
||||
file(GLOB libcarla_carla_streaming_headers "${libcarla_source_path}/carla/streaming/*.h")
|
||||
install(FILES ${libcarla_carla_streaming_headers} DESTINATION include/carla/streaming)
|
||||
|
||||
|
@ -49,6 +64,10 @@ file(GLOB_RECURSE libcarla_server_sources
|
|||
"${libcarla_source_path}/carla/*.cpp"
|
||||
"${libcarla_source_path}/carla/rpc/*.h"
|
||||
"${libcarla_source_path}/carla/rpc/*.cpp"
|
||||
"${libcarla_source_path}/carla/sensor/*.h"
|
||||
"${libcarla_source_path}/carla/sensor/*.cpp"
|
||||
"${libcarla_source_path}/carla/sensor/s11n/*.h"
|
||||
"${libcarla_source_path}/carla/sensor/s11n/*.cpp"
|
||||
"${libcarla_source_path}/carla/streaming/*.h"
|
||||
"${libcarla_source_path}/carla/streaming/*.cpp")
|
||||
|
||||
|
|
|
@ -38,8 +38,9 @@ namespace carla {
|
|||
class Buffer {
|
||||
|
||||
// =========================================================================
|
||||
// -- Typedefs -------------------------------------------------------------
|
||||
/// @name Member types
|
||||
// =========================================================================
|
||||
/// @{
|
||||
|
||||
public:
|
||||
|
||||
|
@ -51,32 +52,37 @@ namespace carla {
|
|||
|
||||
using const_iterator = const value_type *;
|
||||
|
||||
/// @}
|
||||
// =========================================================================
|
||||
// -- Construction and assignment ------------------------------------------
|
||||
/// @name Construction and destruction
|
||||
// =========================================================================
|
||||
/// @{
|
||||
|
||||
public:
|
||||
|
||||
/// Create an empty buffer.
|
||||
Buffer() = default;
|
||||
|
||||
/// Create a buffer with @a size bytes allocated.
|
||||
explicit Buffer(size_type size)
|
||||
: _size(size),
|
||||
_capacity(size),
|
||||
_data(std::make_unique<value_type[]>(size)) {}
|
||||
|
||||
/// @copydoc Buffer(size_type)
|
||||
explicit Buffer(uint64_t size)
|
||||
: Buffer([size]() {
|
||||
DEBUG_ASSERT(size <= max_size());
|
||||
return static_cast<size_type>(size);
|
||||
} ()) {}
|
||||
|
||||
/// Copy @a source into this buffer. Allocates the necessary memory.
|
||||
template <typename T>
|
||||
explicit Buffer(const T &source) {
|
||||
copy_from(source);
|
||||
}
|
||||
|
||||
Buffer(const Buffer &) = delete;
|
||||
Buffer &operator=(const Buffer &) = delete;
|
||||
|
||||
Buffer(Buffer &&rhs) noexcept
|
||||
: _parent_pool(std::move(rhs._parent_pool)),
|
||||
|
@ -84,6 +90,22 @@ namespace carla {
|
|||
_capacity(rhs._capacity),
|
||||
_data(rhs.pop()) {}
|
||||
|
||||
~Buffer() {
|
||||
if (_capacity > 0u) {
|
||||
ReuseThisBuffer();
|
||||
}
|
||||
}
|
||||
|
||||
/// @}
|
||||
// =========================================================================
|
||||
/// @name Assignment
|
||||
// =========================================================================
|
||||
/// @{
|
||||
|
||||
public:
|
||||
|
||||
Buffer &operator=(const Buffer &) = delete;
|
||||
|
||||
Buffer &operator=(Buffer &&rhs) noexcept {
|
||||
_parent_pool = std::move(rhs._parent_pool);
|
||||
_size = rhs._size;
|
||||
|
@ -92,15 +114,60 @@ namespace carla {
|
|||
return *this;
|
||||
}
|
||||
|
||||
~Buffer() {
|
||||
if (_capacity > 0u) {
|
||||
ReuseThisBuffer();
|
||||
}
|
||||
/// @}
|
||||
// =========================================================================
|
||||
/// @name Data access
|
||||
// =========================================================================
|
||||
/// @{
|
||||
|
||||
public:
|
||||
|
||||
/// Access the byte at position @a i.
|
||||
const value_type &operator[](size_t i) const {
|
||||
return _data[i];
|
||||
}
|
||||
|
||||
/// Access the byte at position @a i.
|
||||
value_type &operator[](size_t i) {
|
||||
return _data[i];
|
||||
}
|
||||
|
||||
/// Direct access to the allocated memory or nullptr if no memory is
|
||||
/// allocated.
|
||||
const value_type *data() const noexcept {
|
||||
return _data.get();
|
||||
}
|
||||
|
||||
/// Direct access to the allocated memory or nullptr if no memory is
|
||||
/// allocated.
|
||||
value_type *data() noexcept {
|
||||
return _data.get();
|
||||
}
|
||||
|
||||
/// Make a boost::asio::buffer from this buffer.
|
||||
///
|
||||
/// @warning Boost.Asio buffers do not own the data, it's up to the caller
|
||||
/// to not delete the memory that this buffer holds until the asio buffer is
|
||||
/// no longer used.
|
||||
boost::asio::const_buffer cbuffer() const {
|
||||
return {data(), size()};
|
||||
}
|
||||
|
||||
/// @copydoc cbuffer()
|
||||
boost::asio::const_buffer buffer() const {
|
||||
return cbuffer();
|
||||
}
|
||||
|
||||
/// @copydoc cbuffer()
|
||||
boost::asio::mutable_buffer buffer() {
|
||||
return {data(), size()};
|
||||
}
|
||||
|
||||
/// @}
|
||||
// =========================================================================
|
||||
// -- Data access ----------------------------------------------------------
|
||||
/// @name Capacity
|
||||
// =========================================================================
|
||||
/// @{
|
||||
|
||||
public:
|
||||
|
||||
|
@ -120,25 +187,13 @@ namespace carla {
|
|||
return _capacity;
|
||||
}
|
||||
|
||||
const value_type &operator[](size_t i) const {
|
||||
return _data[i];
|
||||
}
|
||||
|
||||
value_type &operator[](size_t i) {
|
||||
return _data[i];
|
||||
}
|
||||
|
||||
const value_type *data() const noexcept {
|
||||
return _data.get();
|
||||
}
|
||||
|
||||
value_type *data() noexcept {
|
||||
return _data.get();
|
||||
}
|
||||
|
||||
/// @}
|
||||
// =========================================================================
|
||||
// -- Iterators ------------------------------------------------------------
|
||||
/// @name Iterators
|
||||
// =========================================================================
|
||||
/// @{
|
||||
|
||||
public:
|
||||
|
||||
const_iterator cbegin() const noexcept {
|
||||
return _data.get();
|
||||
|
@ -164,12 +219,17 @@ namespace carla {
|
|||
return begin() + size();
|
||||
}
|
||||
|
||||
/// @}
|
||||
// =========================================================================
|
||||
// -- Resizing -------------------------------------------------------------
|
||||
/// @name Modifiers
|
||||
// =========================================================================
|
||||
/// @{
|
||||
|
||||
public:
|
||||
|
||||
/// Reset the size of this buffer. If the capacity is not enough, the
|
||||
/// current memory is discarded and a new block of size @a size is
|
||||
/// allocated.
|
||||
void reset(size_type size) {
|
||||
if (_capacity < size) {
|
||||
log_debug("allocating buffer of", size, "bytes");
|
||||
|
@ -179,75 +239,89 @@ namespace carla {
|
|||
_size = size;
|
||||
}
|
||||
|
||||
/// @copydoc reset(size_type)
|
||||
void reset(uint64_t size) {
|
||||
DEBUG_ASSERT(size <= max_size());
|
||||
reset(static_cast<size_type>(size));
|
||||
}
|
||||
|
||||
/// Release the contents of this buffer and set its size and capacity to
|
||||
/// zero.
|
||||
std::unique_ptr<value_type[]> pop() noexcept {
|
||||
_size = 0u;
|
||||
_capacity = 0u;
|
||||
return std::move(_data);
|
||||
}
|
||||
|
||||
/// Clear the contents of this buffer and set its size and capacity to zero.
|
||||
/// Deletes allocated memory.
|
||||
void clear() noexcept {
|
||||
pop();
|
||||
}
|
||||
|
||||
/// @}
|
||||
// =========================================================================
|
||||
// -- Rewriting ------------------------------------------------------------
|
||||
/// @name copy_from
|
||||
// =========================================================================
|
||||
/// @{
|
||||
|
||||
public:
|
||||
|
||||
/// Copy @a source into this buffer. Allocates memory if necessary.
|
||||
template <typename T>
|
||||
typename std::enable_if<boost::asio::is_const_buffer_sequence<T>::value>::type
|
||||
copy_from(const T &source) {
|
||||
reset(boost::asio::buffer_size(source));
|
||||
DEBUG_ASSERT(boost::asio::buffer_size(source) == size());
|
||||
DEBUG_ONLY(auto bytes_copied = )
|
||||
boost::asio::buffer_copy(buffer(), source);
|
||||
DEBUG_ASSERT(bytes_copied == size());
|
||||
void copy_from(const T &source) {
|
||||
copy_from(0u, source);
|
||||
}
|
||||
|
||||
/// Copy @a size bytes of the memory pointed by @a data into this buffer.
|
||||
/// Allocates memory if necessary.
|
||||
void copy_from(const value_type *data, size_type size) {
|
||||
copy_from(0u, data, size);
|
||||
}
|
||||
|
||||
/// Copy @a source into this buffer leaving at the front an offset of @a
|
||||
/// offset bytes uninitialized. Allocates memory if necessary.
|
||||
void copy_from(size_type offset, const Buffer &rhs) {
|
||||
copy_from(offset, rhs.buffer());
|
||||
}
|
||||
|
||||
/// @copydoc copy_from(size_type, const Buffer &)
|
||||
template <typename T>
|
||||
typename std::enable_if<boost::asio::is_const_buffer_sequence<T>::value>::type
|
||||
copy_from(size_type offset, const T &source) {
|
||||
reset(boost::asio::buffer_size(source) + offset);
|
||||
DEBUG_ASSERT(boost::asio::buffer_size(source) == size() - offset);
|
||||
DEBUG_ONLY(auto bytes_copied = )
|
||||
boost::asio::buffer_copy(buffer() + offset, source);
|
||||
DEBUG_ASSERT(bytes_copied == size() - offset);
|
||||
}
|
||||
|
||||
/// @copydoc copy_from(size_type, const Buffer &)
|
||||
template <typename T>
|
||||
typename std::enable_if<!boost::asio::is_const_buffer_sequence<T>::value>::type
|
||||
copy_from(const T &source) {
|
||||
copy_from(boost::asio::buffer(source));
|
||||
copy_from(size_type offset, const T &source) {
|
||||
copy_from(offset, boost::asio::buffer(source));
|
||||
}
|
||||
|
||||
#ifdef LIBCARLA_INCLUDED_FROM_UE4
|
||||
/// @copydoc copy_from(size_type, const Buffer &)
|
||||
template <typename T>
|
||||
void copy_from(const TArray<T> &source) {
|
||||
copy_from(boost::asio::buffer(source.GetData(), sizeof(T) * source.Num()));
|
||||
void copy_from(size_type offset, const TArray<T> &source) {
|
||||
copy_from(
|
||||
offset,
|
||||
reinterpret_cast<const value_type *>(source.GetData()),
|
||||
sizeof(T) * source.Num());
|
||||
}
|
||||
#endif // LIBCARLA_INCLUDED_FROM_UE4
|
||||
|
||||
void copy_from(const Buffer &rhs) {
|
||||
copy_from(rhs.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.
|
||||
/// Allocates memory if necessary.
|
||||
void copy_from(size_t offset, const value_type *data, size_type size) {
|
||||
copy_from(offset, boost::asio::buffer(data, size));
|
||||
}
|
||||
|
||||
// =========================================================================
|
||||
// -- Conversions ----------------------------------------------------------
|
||||
// =========================================================================
|
||||
|
||||
public:
|
||||
|
||||
boost::asio::const_buffer cbuffer() const {
|
||||
return {data(), size()};
|
||||
}
|
||||
|
||||
boost::asio::const_buffer buffer() const {
|
||||
return cbuffer();
|
||||
}
|
||||
|
||||
boost::asio::mutable_buffer buffer() {
|
||||
return {data(), size()};
|
||||
}
|
||||
|
||||
// =========================================================================
|
||||
// -- Private members ------------------------------------------------------
|
||||
// =========================================================================
|
||||
/// @}
|
||||
|
||||
private:
|
||||
|
||||
|
|
|
@ -17,6 +17,7 @@
|
|||
#endif // NDEBUG
|
||||
|
||||
#define DEBUG_ASSERT(predicate) DEBUG_ONLY(assert(predicate));
|
||||
#define DEBUG_ERROR DEBUG_ASSERT(false);
|
||||
|
||||
#ifdef LIBCARLA_WITH_GTEST
|
||||
# include <gtest/gtest.h>
|
||||
|
|
|
@ -0,0 +1,26 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "carla/FileSystem.h"
|
||||
|
||||
#include <boost/filesystem/operations.hpp>
|
||||
|
||||
namespace carla {
|
||||
|
||||
void FileSystem::ValidateFilePath(std::string &filepath, const std::string &ext) {
|
||||
namespace fs = boost::filesystem;
|
||||
fs::path path(filepath);
|
||||
if (path.extension().empty() && !ext.empty()) {
|
||||
if (ext[0] != '.') {
|
||||
path += '.';
|
||||
}
|
||||
path += ext;
|
||||
}
|
||||
fs::create_directories(path.parent_path());
|
||||
filepath = path.string();
|
||||
}
|
||||
|
||||
} // namespace carla
|
|
@ -0,0 +1,29 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <string>
|
||||
|
||||
namespace carla {
|
||||
|
||||
/// Static functions for accessing the file system.
|
||||
///
|
||||
/// @warning Using this file requires linking against boost_filesystem.
|
||||
class FileSystem {
|
||||
public:
|
||||
|
||||
/// Convenient function to validate a path before creating a file.
|
||||
///
|
||||
/// 1) Ensures all the parent directories are created if missing.
|
||||
/// 2) If @a filepath is missing the extension, @a default_extension is
|
||||
/// appended to the path.
|
||||
static void ValidateFilePath(
|
||||
std::string &filepath,
|
||||
const std::string &default_extension = "");
|
||||
};
|
||||
|
||||
} // namespace carla
|
|
@ -6,26 +6,24 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
// In this namespace, we use boost::shared_ptr for now to make it compatible
|
||||
// with boost::python, but it would be nice to make an adaptor for
|
||||
// std::shared_ptr.
|
||||
#include <boost/enable_shared_from_this.hpp>
|
||||
#include <boost/make_shared.hpp>
|
||||
#include <boost/shared_ptr.hpp>
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
|
||||
/// Use this SharedPtr (boost::shared_ptr) to keep compatibility with
|
||||
/// boost::python, but it would be nice if in the future we can make a Python
|
||||
/// adaptor for std::shared_ptr.
|
||||
template <typename T>
|
||||
using SharedPtr = boost::shared_ptr<T>;
|
||||
|
||||
template <typename T>
|
||||
using EnableSharedFromThis = boost::enable_shared_from_this<T>;
|
||||
|
||||
template <typename T>
|
||||
using SharedPtr = boost::shared_ptr<T>;
|
||||
|
||||
template <typename T, typename ... Args>
|
||||
static inline auto MakeShared(Args && ... args) {
|
||||
return boost::make_shared<T>(std::forward<Args>(args) ...);
|
||||
template <typename T, typename... Args>
|
||||
static inline auto MakeShared(Args &&... args) {
|
||||
return boost::make_shared<T>(std::forward<Args>(args)...);
|
||||
}
|
||||
|
||||
} // namespace client
|
||||
} // namespace carla
|
|
@ -8,15 +8,30 @@
|
|||
|
||||
namespace carla {
|
||||
|
||||
/// Inherit (privately) to suppress copy-construction and copy-assignment.
|
||||
/// Inherit (privately) to suppress copy/move construction and assignment.
|
||||
class NonCopyable {
|
||||
public:
|
||||
|
||||
NonCopyable() = default;
|
||||
|
||||
NonCopyable(const NonCopyable &) = delete;
|
||||
NonCopyable &operator=(const NonCopyable &) = delete;
|
||||
|
||||
void operator=(const NonCopyable &) = delete;
|
||||
NonCopyable(NonCopyable &&) = delete;
|
||||
NonCopyable &operator=(NonCopyable &&) = delete;
|
||||
};
|
||||
|
||||
/// Inherit (privately) to suppress copy construction and assignment.
|
||||
class MovableNonCopyable {
|
||||
public:
|
||||
|
||||
MovableNonCopyable() = default;
|
||||
|
||||
MovableNonCopyable(const MovableNonCopyable &) = delete;
|
||||
MovableNonCopyable &operator=(const MovableNonCopyable &) = delete;
|
||||
|
||||
MovableNonCopyable(MovableNonCopyable &&) = default;
|
||||
MovableNonCopyable &operator=(MovableNonCopyable &&) = default;
|
||||
};
|
||||
|
||||
} // namespace carla
|
||||
|
|
|
@ -0,0 +1,36 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <boost/optional.hpp>
|
||||
|
||||
namespace carla {
|
||||
|
||||
template <typename T>
|
||||
class Optional : private boost::optional<T> {
|
||||
using parent_type = boost::optional<T>;
|
||||
public:
|
||||
|
||||
template <typename... Args>
|
||||
explicit Optional(Args &&... args)
|
||||
: parent_type(std::forward<Args>(args)...) {}
|
||||
|
||||
using parent_type::operator*;
|
||||
using parent_type::operator->;
|
||||
using parent_type::operator=;
|
||||
using parent_type::emplace;
|
||||
using parent_type::reset;
|
||||
using parent_type::swap;
|
||||
// using parent_type::value; disabled to avoid exceptions.
|
||||
using parent_type::value_or;
|
||||
|
||||
bool has_value() const {
|
||||
return parent_type::is_initialized();
|
||||
}
|
||||
};
|
||||
|
||||
} // namespace carla
|
|
@ -0,0 +1,109 @@
|
|||
// 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/NonCopyable.h"
|
||||
|
||||
#ifdef LIBCARLA_WITH_PYTHON_SUPPORT
|
||||
# include <boost/python.hpp>
|
||||
#endif // LIBCARLA_WITH_PYTHON_SUPPORT
|
||||
|
||||
namespace carla {
|
||||
|
||||
class PythonUtil {
|
||||
public:
|
||||
|
||||
static bool ThisThreadHasTheGIL() {
|
||||
#ifdef LIBCARLA_WITH_PYTHON_SUPPORT
|
||||
# ifdef PYTHON3X
|
||||
return PyGILState_Check();
|
||||
# else
|
||||
PyThreadState *tstate = _PyThreadState_Current;
|
||||
return (tstate != nullptr) && (tstate == PyGILState_GetThisThreadState());
|
||||
# endif // PYTHON3
|
||||
#else
|
||||
return false;
|
||||
#endif // LIBCARLA_WITH_PYTHON_SUPPORT
|
||||
}
|
||||
|
||||
#ifdef LIBCARLA_WITH_PYTHON_SUPPORT
|
||||
|
||||
/// Acquires a lock on the Python's Global Interpreter Lock, necessary for
|
||||
/// calling Python code from a different thread.
|
||||
class AcquireGIL : private NonCopyable {
|
||||
public:
|
||||
|
||||
AcquireGIL() : _state(PyGILState_Ensure()) {}
|
||||
|
||||
~AcquireGIL() {
|
||||
PyGILState_Release(_state);
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
PyGILState_STATE _state;
|
||||
};
|
||||
|
||||
/// Releases the lock on the Python's Global Interpreter Lock, use it when doing
|
||||
/// blocking I/O operations.
|
||||
class ReleaseGIL : private NonCopyable {
|
||||
public:
|
||||
|
||||
ReleaseGIL() : _state(PyEval_SaveThread()) {}
|
||||
|
||||
~ReleaseGIL() {
|
||||
PyEval_RestoreThread(_state);
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
PyThreadState *_state;
|
||||
};
|
||||
|
||||
#else // LIBCARLA_WITH_PYTHON_SUPPORT
|
||||
|
||||
class AcquireGIL : private NonCopyable {};
|
||||
class ReleaseGIL : private NonCopyable {};
|
||||
|
||||
#endif // LIBCARLA_WITH_PYTHON_SUPPORT
|
||||
|
||||
/// A deleter that can be passed to a smart pointer to acquire the GIL
|
||||
/// before destroying the object.
|
||||
class AcquireGILDeleter {
|
||||
public:
|
||||
|
||||
template <typename T>
|
||||
void operator()(T *ptr) const {
|
||||
#ifdef LIBCARLA_WITH_PYTHON_SUPPORT
|
||||
if (ptr != nullptr && !PythonUtil::ThisThreadHasTheGIL()) {
|
||||
AcquireGIL lock;
|
||||
delete ptr;
|
||||
} else
|
||||
#endif // LIBCARLA_WITH_PYTHON_SUPPORT
|
||||
delete ptr;
|
||||
}
|
||||
};
|
||||
|
||||
/// A deleter that can be passed to a smart pointer to release the GIL
|
||||
/// before destroying the object.
|
||||
class ReleaseGILDeleter {
|
||||
public:
|
||||
|
||||
template <typename T>
|
||||
void operator()(T *ptr) const {
|
||||
#ifdef LIBCARLA_WITH_PYTHON_SUPPORT
|
||||
if (ptr != nullptr && PythonUtil::ThisThreadHasTheGIL()) {
|
||||
ReleaseGIL lock;
|
||||
delete ptr;
|
||||
} else
|
||||
#endif // LIBCARLA_WITH_PYTHON_SUPPORT
|
||||
delete ptr;
|
||||
}
|
||||
};
|
||||
};
|
||||
|
||||
} // namespace carla
|
|
@ -14,11 +14,11 @@
|
|||
|
||||
namespace carla {
|
||||
|
||||
bool StringUtil::Match(const std::string &str, const std::string &test) {
|
||||
bool StringUtil::Match(const char *str, const char *test) {
|
||||
#ifdef _WIN32
|
||||
return PathMatchSpecA(str.c_str(), test.c_str());
|
||||
return PathMatchSpecA(str, test);
|
||||
#else
|
||||
return 0 == fnmatch(test.c_str(), str.c_str(), 0);
|
||||
return 0 == fnmatch(test, str, 0);
|
||||
#endif // _WIN32
|
||||
}
|
||||
|
||||
|
|
|
@ -8,29 +8,73 @@
|
|||
|
||||
#include <boost/algorithm/string.hpp>
|
||||
|
||||
#include <algorithm>
|
||||
#include <string>
|
||||
|
||||
namespace carla {
|
||||
|
||||
class StringUtil {
|
||||
public:
|
||||
|
||||
static void ToLower(std::string &str) {
|
||||
static const char *ToConstCharPtr(const char *str) {
|
||||
return str;
|
||||
}
|
||||
|
||||
template <typename StringT>
|
||||
static const char *ToConstCharPtr(const StringT &str) {
|
||||
return str.c_str();
|
||||
}
|
||||
|
||||
template <typename Range1T, typename Range2T>
|
||||
static bool StartsWith(const Range1T &input, const Range2T &test) {
|
||||
return boost::algorithm::istarts_with(input, test);
|
||||
}
|
||||
|
||||
template <typename Range1T, typename Range2T>
|
||||
static bool EndsWith(const Range1T &input, const Range2T &test) {
|
||||
return boost::algorithm::iends_with(input, test);
|
||||
}
|
||||
|
||||
template <typename WritableRangeT>
|
||||
static void ToLower(WritableRangeT &str) {
|
||||
boost::algorithm::to_lower(str);
|
||||
}
|
||||
|
||||
static std::string ToLowerCopy(const std::string &str) {
|
||||
template <typename SequenceT>
|
||||
static auto ToLowerCopy(const SequenceT &str) {
|
||||
return boost::algorithm::to_lower_copy(str);
|
||||
}
|
||||
|
||||
template <typename Container>
|
||||
static void Split(Container &destination, const std::string &str, const std::string &separators) {
|
||||
template <typename WritableRangeT>
|
||||
static void ToUpper(WritableRangeT &str) {
|
||||
boost::algorithm::to_upper(str);
|
||||
}
|
||||
|
||||
template <typename SequenceT>
|
||||
static auto ToUpperCopy(const SequenceT &str) {
|
||||
return boost::algorithm::to_upper_copy(str);
|
||||
}
|
||||
|
||||
template <typename WritableRangeT>
|
||||
static void Trim(WritableRangeT &str) {
|
||||
boost::algorithm::trim(str);
|
||||
}
|
||||
|
||||
template <typename SequenceT>
|
||||
static auto TrimCopy(const SequenceT &str) {
|
||||
return boost::algorithm::trim_copy(str);
|
||||
}
|
||||
|
||||
template<typename Container, typename Range1T, typename Range2T>
|
||||
static void Split(Container &destination, const Range1T &str, const Range2T &separators) {
|
||||
boost::split(destination, str, boost::is_any_of(separators));
|
||||
}
|
||||
|
||||
/// Match @a str with the Unix shell-style @a wildcard_pattern.
|
||||
static bool Match(const std::string &str, const std::string &wildcard_pattern);
|
||||
static bool Match(const char *str, const char *wildcard_pattern);
|
||||
|
||||
/// Match @a str with the Unix shell-style @a wildcard_pattern.
|
||||
template <typename String1T, typename String2T>
|
||||
static bool Match(const String1T &str, const String2T &wildcard_pattern) {
|
||||
return Match(ToConstCharPtr(str), ToConstCharPtr(wildcard_pattern));
|
||||
}
|
||||
};
|
||||
|
||||
} // namespace carla
|
||||
|
|
|
@ -37,6 +37,7 @@ namespace carla {
|
|||
|
||||
void JoinAll() {
|
||||
for (auto &thread : _threads) {
|
||||
DEBUG_ASSERT_NE(thread.get_id(), std::this_thread::get_id());
|
||||
if (thread.joinable()) {
|
||||
thread.join();
|
||||
}
|
||||
|
|
|
@ -5,29 +5,38 @@
|
|||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "carla/client/Actor.h"
|
||||
#include "carla/client/Client.h"
|
||||
|
||||
#include "carla/Logging.h"
|
||||
#include "carla/client/detail/Client.h"
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
|
||||
Location Actor::GetLocation() {
|
||||
return GetWorld()->GetClient().GetActorLocation(*this);
|
||||
geom::Location Actor::GetLocation() const {
|
||||
return GetEpisode()->GetActorLocation(*this);
|
||||
}
|
||||
|
||||
Transform Actor::GetTransform() {
|
||||
return GetWorld()->GetClient().GetActorTransform(*this);
|
||||
geom::Transform Actor::GetTransform() const {
|
||||
return GetEpisode()->GetActorTransform(*this);
|
||||
}
|
||||
|
||||
bool Actor::SetLocation(const Location &location) {
|
||||
return GetWorld()->GetClient().SetActorLocation(*this, location);
|
||||
void Actor::SetLocation(const geom::Location &location) {
|
||||
GetEpisode()->SetActorLocation(*this, location);
|
||||
}
|
||||
|
||||
bool Actor::SetTransform(const Transform &transform) {
|
||||
return GetWorld()->GetClient().SetActorTransform(*this, transform);
|
||||
void Actor::SetTransform(const geom::Transform &transform) {
|
||||
GetEpisode()->SetActorTransform(*this, transform);
|
||||
}
|
||||
|
||||
void Actor::Destroy() {
|
||||
GetWorld()->GetClient().DestroyActor(*this);
|
||||
if (_is_alive) {
|
||||
// Let the exceptions leave the function, IsAlive() will still be true.
|
||||
_is_alive = !GetEpisode()->DestroyActor(*this);
|
||||
} else {
|
||||
log_warning(
|
||||
"attempting to destroy an actor that is already dead:",
|
||||
GetDisplayId());
|
||||
}
|
||||
}
|
||||
|
||||
} // namespace client
|
||||
|
|
|
@ -7,67 +7,47 @@
|
|||
#pragma once
|
||||
|
||||
#include "carla/Debug.h"
|
||||
#include "carla/NonCopyable.h"
|
||||
#include "carla/client/Memory.h"
|
||||
#include "carla/client/World.h"
|
||||
#include "carla/rpc/Actor.h"
|
||||
#include "carla/Memory.h"
|
||||
#include "carla/client/detail/ActorState.h"
|
||||
#include "carla/profiler/LifetimeProfiled.h"
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
|
||||
class Client;
|
||||
|
||||
class Actor
|
||||
: public EnableSharedFromThis<Actor>,
|
||||
private NonCopyable {
|
||||
private profiler::LifetimeProfiled,
|
||||
public detail::ActorState {
|
||||
using Super = detail::ActorState;
|
||||
public:
|
||||
|
||||
explicit Actor(ActorInitializer init)
|
||||
: LIBCARLA_INITIALIZE_LIFETIME_PROFILER(init.GetDisplayId()),
|
||||
Super(std::move(init)) {}
|
||||
|
||||
virtual ~Actor() = default;
|
||||
|
||||
Actor(Actor &&) = default;
|
||||
Actor &operator=(Actor &&) = default;
|
||||
geom::Location GetLocation() const;
|
||||
|
||||
auto GetId() const {
|
||||
return _actor.id;
|
||||
}
|
||||
geom::Transform GetTransform() const;
|
||||
|
||||
const std::string &GetTypeId() const {
|
||||
return _actor.description.id;
|
||||
}
|
||||
void SetLocation(const geom::Location &location);
|
||||
|
||||
SharedPtr<World> GetWorld() const {
|
||||
return _world;
|
||||
}
|
||||
|
||||
Location GetLocation();
|
||||
|
||||
Transform GetTransform();
|
||||
|
||||
bool SetLocation(const Location &location);
|
||||
|
||||
bool SetTransform(const Transform &transform);
|
||||
void SetTransform(const geom::Transform &transform);
|
||||
|
||||
const auto &Serialize() const {
|
||||
return _actor;
|
||||
return Super::GetActorDescription();
|
||||
}
|
||||
|
||||
void Destroy();
|
||||
|
||||
protected:
|
||||
|
||||
Actor(carla::rpc::Actor actor, SharedPtr<World> world)
|
||||
: _actor(actor),
|
||||
_world(std::move(world)) {
|
||||
DEBUG_ASSERT(_world != nullptr);
|
||||
bool IsAlive() const {
|
||||
return _is_alive;
|
||||
}
|
||||
|
||||
virtual void Destroy();
|
||||
|
||||
private:
|
||||
|
||||
friend class Client;
|
||||
|
||||
carla::rpc::Actor _actor;
|
||||
|
||||
SharedPtr<World> _world;
|
||||
bool _is_alive = true;
|
||||
};
|
||||
|
||||
} // namespace client
|
||||
|
|
|
@ -65,7 +65,7 @@ namespace client {
|
|||
}
|
||||
|
||||
template <>
|
||||
Color ActorAttribute::As<Color>() const {
|
||||
sensor::data::Color ActorAttribute::As<sensor::data::Color>() const {
|
||||
LIBCARLA_THROW_BAD_VALUE_CAST(RGBColor);
|
||||
|
||||
std::vector<std::string> channels;
|
||||
|
|
|
@ -6,8 +6,8 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "carla/client/Color.h"
|
||||
#include "carla/rpc/ActorAttribute.h"
|
||||
#include "carla/sensor/data/Color.h"
|
||||
|
||||
#include <cstdlib>
|
||||
#include <exception>
|
||||
|
@ -121,7 +121,7 @@ namespace client {
|
|||
std::string ActorAttribute::As<std::string>() const;
|
||||
|
||||
template <>
|
||||
Color ActorAttribute::As<Color>() const;
|
||||
sensor::data::Color ActorAttribute::As<sensor::data::Color>() const;
|
||||
|
||||
template <>
|
||||
inline auto ActorAttribute::As<rpc::ActorAttributeType::Bool>() const {
|
||||
|
@ -145,7 +145,7 @@ namespace client {
|
|||
|
||||
template <>
|
||||
inline auto ActorAttribute::As<rpc::ActorAttributeType::RGBColor>() const {
|
||||
return As<Color>();
|
||||
return As<sensor::data::Color>();
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
|
|
|
@ -35,6 +35,19 @@ namespace client {
|
|||
});
|
||||
}
|
||||
|
||||
const ActorAttribute &ActorBlueprint::GetAttribute(const std::string &id) const {
|
||||
auto it = _attributes.find(id);
|
||||
if (it == _attributes.end()) {
|
||||
using namespace std::string_literals;
|
||||
throw std::out_of_range("attribute '"s + id + "' not found");
|
||||
}
|
||||
return it->second;
|
||||
}
|
||||
|
||||
void ActorBlueprint::SetAttribute(const std::string &id, std::string value) {
|
||||
const_cast<ActorAttribute &>(GetAttribute(id)).Set(std::move(value));
|
||||
}
|
||||
|
||||
rpc::ActorDescription ActorBlueprint::MakeActorDescription() const {
|
||||
rpc::ActorDescription description;
|
||||
description.uid = _uid;
|
||||
|
|
|
@ -76,18 +76,14 @@ namespace client {
|
|||
}
|
||||
|
||||
/// @throw std::out_of_range if no such element exists.
|
||||
const ActorAttribute &GetAttribute(const std::string &id) const {
|
||||
return _attributes.at(id);
|
||||
}
|
||||
const ActorAttribute &GetAttribute(const std::string &id) const;
|
||||
|
||||
/// Set the value of the attribute given by @a id.
|
||||
///
|
||||
/// @throw std::out_of_range if no such element exists.
|
||||
/// @throw InvalidAttributeValue if attribute is not modifiable.
|
||||
/// @throw InvalidAttributeValue if format does not match the attribute type.
|
||||
void SetAttribute(const std::string &id, std::string value) {
|
||||
_attributes.at(id).Set(std::move(value));
|
||||
}
|
||||
void SetAttribute(const std::string &id, std::string value);
|
||||
|
||||
size_t size() const {
|
||||
return _attributes.size();
|
||||
|
|
|
@ -31,6 +31,20 @@ namespace client {
|
|||
return SharedPtr<BlueprintLibrary>{new BlueprintLibrary(result)};
|
||||
}
|
||||
|
||||
BlueprintLibrary::const_pointer BlueprintLibrary::Find(const std::string &key) const {
|
||||
auto it = _blueprints.find(key);
|
||||
return it != _blueprints.end() ? &it->second : nullptr;
|
||||
}
|
||||
|
||||
BlueprintLibrary::const_reference BlueprintLibrary::at(const std::string &key) const {
|
||||
auto it = _blueprints.find(key);
|
||||
if (it == _blueprints.end()) {
|
||||
using namespace std::string_literals;
|
||||
throw std::out_of_range("blueprint '"s + key + "' not found");
|
||||
}
|
||||
return it->second;
|
||||
}
|
||||
|
||||
BlueprintLibrary::const_reference BlueprintLibrary::at(size_type pos) const {
|
||||
if (pos >= size())
|
||||
throw std::out_of_range("index out of range");
|
||||
|
|
|
@ -8,9 +8,9 @@
|
|||
|
||||
#include "carla/Debug.h"
|
||||
#include "carla/Iterator.h"
|
||||
#include "carla/Memory.h"
|
||||
#include "carla/NonCopyable.h"
|
||||
#include "carla/client/ActorBlueprint.h"
|
||||
#include "carla/client/Memory.h"
|
||||
|
||||
#include <type_traits>
|
||||
#include <unordered_map>
|
||||
|
@ -43,14 +43,10 @@ namespace client {
|
|||
/// Filters a list of ActorBlueprint with tags matching @a wildcard_pattern.
|
||||
SharedPtr<BlueprintLibrary> Filter(const std::string &wildcard_pattern) const;
|
||||
|
||||
const_pointer Find(const std::string &key) const {
|
||||
auto it = _blueprints.find(key);
|
||||
return it != _blueprints.end() ? &it->second : nullptr;
|
||||
}
|
||||
const_pointer Find(const std::string &key) const;
|
||||
|
||||
const_reference at(const std::string &key) const {
|
||||
return _blueprints.at(key);
|
||||
}
|
||||
/// @throw std::out_of_range if no such element exists.
|
||||
const_reference at(const std::string &key) const;
|
||||
|
||||
/// @warning Linear complexity.
|
||||
const_reference operator[](size_type pos) const {
|
||||
|
@ -58,6 +54,7 @@ namespace client {
|
|||
}
|
||||
|
||||
/// @warning Linear complexity.
|
||||
/// @throw std::out_of_range if !(pos < size()).
|
||||
const_reference at(size_type pos) const;
|
||||
|
||||
const_iterator begin() const /*noexcept*/ {
|
||||
|
|
|
@ -1,91 +0,0 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "carla/client/Client.h"
|
||||
|
||||
#include "carla/client/Actor.h"
|
||||
#include "carla/client/BlueprintLibrary.h"
|
||||
#include "carla/client/Control.h"
|
||||
#include "carla/client/Sensor.h"
|
||||
#include "carla/client/Vehicle.h"
|
||||
#include "carla/client/World.h"
|
||||
|
||||
#include <thread>
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
|
||||
Client::Client(const std::string &host, uint16_t port, size_t worker_threads)
|
||||
: _client(host, port),
|
||||
_streaming_client(host) {
|
||||
_streaming_client.AsyncRun(
|
||||
worker_threads > 0u ? worker_threads : std::thread::hardware_concurrency());
|
||||
}
|
||||
|
||||
SharedPtr<World> Client::GetWorld() {
|
||||
if (_active_world == nullptr) {
|
||||
_active_world.reset(new World(shared_from_this()));
|
||||
}
|
||||
return _active_world;
|
||||
}
|
||||
|
||||
SharedPtr<BlueprintLibrary> Client::GetBlueprintLibrary() {
|
||||
return MakeShared<BlueprintLibrary>(
|
||||
Call<std::vector<carla::rpc::ActorDefinition>>("get_actor_definitions"));
|
||||
}
|
||||
|
||||
SharedPtr<Actor> Client::GetSpectator() {
|
||||
auto spectator = Call<carla::rpc::Actor>("get_spectator");
|
||||
return SharedPtr<Actor>(new Actor{spectator, GetWorld()});
|
||||
}
|
||||
|
||||
SharedPtr<Actor> Client::SpawnActor(
|
||||
const ActorBlueprint &blueprint,
|
||||
const Transform &transform,
|
||||
Actor *parent) {
|
||||
auto actor = parent != nullptr ?
|
||||
Call<carla::rpc::Actor>("spawn_actor_with_parent", transform, blueprint.MakeActorDescription(), parent->Serialize()) :
|
||||
Call<carla::rpc::Actor>("spawn_actor", transform, blueprint.MakeActorDescription());
|
||||
if (actor.IsASensor()) {
|
||||
return SharedPtr<Actor>(new Sensor{actor, GetWorld()});
|
||||
}
|
||||
return SharedPtr<Actor>(new Vehicle{actor, GetWorld()});
|
||||
}
|
||||
|
||||
void Client::DestroyActor(Actor &actor) {
|
||||
_client.call("destroy_actor", actor.Serialize());
|
||||
}
|
||||
|
||||
Location Client::GetActorLocation(Actor &actor) {
|
||||
return Call<Location>("get_actor_location", actor.Serialize());
|
||||
}
|
||||
|
||||
Transform Client::GetActorTransform(Actor &actor) {
|
||||
return Call<Transform>("get_actor_transform", actor.Serialize());
|
||||
}
|
||||
|
||||
bool Client::SetActorLocation(Actor &actor, const Location &location) {
|
||||
return Call<bool>("set_actor_location", actor.Serialize(), location);
|
||||
}
|
||||
|
||||
bool Client::SetActorTransform(Actor &actor, const Transform &transform) {
|
||||
return Call<bool>("set_actor_transform", actor.Serialize(), transform);
|
||||
}
|
||||
|
||||
void Client::ApplyControlToActor(
|
||||
Actor &actor,
|
||||
const VehicleControl &control) {
|
||||
_client.call("apply_control_to_actor", actor.Serialize(), control);
|
||||
}
|
||||
|
||||
void Client::SetActorAutopilot(
|
||||
Actor &actor,
|
||||
const bool enabled) {
|
||||
_client.call("set_actor_autopilot", actor.Serialize(), enabled);
|
||||
}
|
||||
|
||||
} // namespace client
|
||||
} // namespace carla
|
|
@ -6,28 +6,13 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "carla/NonCopyable.h"
|
||||
#include "carla/Time.h"
|
||||
#include "carla/Version.h"
|
||||
#include "carla/client/Control.h"
|
||||
#include "carla/client/Memory.h"
|
||||
#include "carla/client/Transform.h"
|
||||
#include "carla/rpc/Client.h"
|
||||
#include "carla/streaming/Client.h"
|
||||
|
||||
#include <string>
|
||||
#include "carla/PythonUtil.h"
|
||||
#include "carla/client/detail/Client.h"
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
|
||||
class Actor;
|
||||
class ActorBlueprint;
|
||||
class BlueprintLibrary;
|
||||
class World;
|
||||
|
||||
class Client
|
||||
: public EnableSharedFromThis<Client>,
|
||||
private NonCopyable {
|
||||
class Client {
|
||||
public:
|
||||
|
||||
/// Construct a carla client.
|
||||
|
@ -42,68 +27,37 @@ namespace client {
|
|||
size_t worker_threads = 0u);
|
||||
|
||||
void SetTimeout(time_duration timeout) {
|
||||
_client.set_timeout(timeout.milliseconds());
|
||||
}
|
||||
|
||||
template <typename T, typename ... Args>
|
||||
T Call(const std::string &function, Args && ... args) {
|
||||
return _client.call(function, std::forward<Args>(args) ...).template as<T>();
|
||||
}
|
||||
|
||||
template <typename Functor>
|
||||
void SubscribeToStream(const streaming::Token &token, Functor &&callback) {
|
||||
_streaming_client.Subscribe(token, std::forward<Functor>(callback));
|
||||
_client_state->SetTimeout(timeout);
|
||||
}
|
||||
|
||||
std::string GetClientVersion() const {
|
||||
return ::carla::version();
|
||||
return _client_state->GetClientVersion();
|
||||
}
|
||||
|
||||
std::string GetServerVersion() {
|
||||
return Call<std::string>("version");
|
||||
std::string GetServerVersion() const {
|
||||
return _client_state->GetServerVersion();
|
||||
}
|
||||
|
||||
bool Ping() {
|
||||
return Call<bool>("ping");
|
||||
bool Ping() const {
|
||||
return _client_state->Ping();
|
||||
}
|
||||
|
||||
SharedPtr<World> GetWorld();
|
||||
|
||||
SharedPtr<BlueprintLibrary> GetBlueprintLibrary();
|
||||
|
||||
SharedPtr<Actor> GetSpectator();
|
||||
|
||||
SharedPtr<Actor> SpawnActor(
|
||||
const ActorBlueprint &blueprint,
|
||||
const Transform &transform,
|
||||
Actor *parent = nullptr);
|
||||
|
||||
void DestroyActor(Actor &actor);
|
||||
|
||||
Location GetActorLocation(Actor &actor);
|
||||
|
||||
Transform GetActorTransform(Actor &actor);
|
||||
|
||||
bool SetActorLocation(Actor &actor, const Location &location);
|
||||
|
||||
bool SetActorTransform(Actor &actor, const Transform &transform);
|
||||
|
||||
void ApplyControlToActor(
|
||||
Actor &actor,
|
||||
const VehicleControl &control);
|
||||
|
||||
void SetActorAutopilot(
|
||||
Actor &actor,
|
||||
bool enabled = true);
|
||||
World GetWorld() const {
|
||||
return _client_state->GetCurrentEpisode();
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
carla::rpc::Client _client;
|
||||
|
||||
carla::streaming::Client _streaming_client;
|
||||
|
||||
SharedPtr<World> _active_world;
|
||||
SharedPtr<detail::Client> _client_state;
|
||||
};
|
||||
|
||||
inline Client::Client(
|
||||
const std::string &host,
|
||||
uint16_t port,
|
||||
size_t worker_threads)
|
||||
: _client_state(
|
||||
new detail::Client(host, port, worker_threads),
|
||||
PythonUtil::ReleaseGILDeleter()) {}
|
||||
|
||||
} // namespace client
|
||||
} // namespace carla
|
||||
|
|
|
@ -6,12 +6,14 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "carla/rpc/VehicleControl.h"
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
|
||||
using VehicleControl = carla::rpc::VehicleControl;
|
||||
enum class GarbageCollectionPolicy {
|
||||
Disabled,
|
||||
Enabled,
|
||||
Inherit
|
||||
};
|
||||
|
||||
} // namespace client
|
||||
} // namespace carla
|
|
@ -1,86 +0,0 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "carla/Debug.h"
|
||||
#include "carla/client/Image.h"
|
||||
|
||||
#include <cstdint>
|
||||
#include <cstring>
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
|
||||
/// @todo This object should be shared and packed.
|
||||
struct FImageHeaderData
|
||||
{
|
||||
uint64_t FrameNumber;
|
||||
uint32_t Width;
|
||||
uint32_t Height;
|
||||
uint32_t Type;
|
||||
float FOV;
|
||||
};
|
||||
|
||||
static std::string GetTypeString(uint32_t type) {
|
||||
switch (type) {
|
||||
case 0u: return "None";
|
||||
case 1u: return "SceneFinal";
|
||||
case 2u: return "Depth";
|
||||
case 3u: return "SemanticSegmentation";
|
||||
default: return "Invalid";
|
||||
}
|
||||
}
|
||||
|
||||
SharedPtr<Image> Image::FromBuffer(Buffer buffer) {
|
||||
/// @todo We can avoid making another copy of the buffer here.
|
||||
if (buffer.size() < sizeof(FImageHeaderData)) {
|
||||
throw std::invalid_argument("buffer too small to be an image");
|
||||
}
|
||||
auto begin = reinterpret_cast<const byte_type *>(buffer.data());
|
||||
auto image = MakeShared<Image>();
|
||||
FImageHeaderData data;
|
||||
std::memcpy(&data, begin, sizeof(data));
|
||||
image->_frame_number = data.FrameNumber;
|
||||
image->_width = data.Width;
|
||||
image->_height = data.Height;
|
||||
image->_type = GetTypeString(data.Type);
|
||||
image->_fov = data.FOV;
|
||||
const auto size = image->GetSize();
|
||||
DEBUG_ASSERT((size + sizeof(FImageHeaderData)) == buffer.size());
|
||||
auto raw_data = std::make_unique<byte_type[]>(size);
|
||||
std::memcpy(raw_data.get(), begin + sizeof(FImageHeaderData), size);
|
||||
image->_raw_data = std::move(raw_data);
|
||||
return image;
|
||||
}
|
||||
|
||||
Image::Image() {
|
||||
Clear();
|
||||
}
|
||||
|
||||
Image::Image(Image &&rhs) {
|
||||
(*this) = std::move(rhs);
|
||||
}
|
||||
|
||||
Image &Image::operator=(Image &&rhs) {
|
||||
_width = rhs._width;
|
||||
_height = rhs._height;
|
||||
_type = rhs._type;
|
||||
_fov = rhs._fov;
|
||||
_raw_data = std::move(rhs._raw_data);
|
||||
rhs.Clear();
|
||||
return *this;
|
||||
}
|
||||
|
||||
void Image::Clear() {
|
||||
_frame_number = 0u;
|
||||
_width = 0u;
|
||||
_height = 0u;
|
||||
_type = "Invalid";
|
||||
_fov = 0.0f;
|
||||
_raw_data = nullptr;
|
||||
}
|
||||
|
||||
} // namespace client
|
||||
} // namespace carla
|
|
@ -1,82 +0,0 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "carla/Buffer.h"
|
||||
#include "carla/NonCopyable.h"
|
||||
#include "carla/client/Memory.h"
|
||||
|
||||
#include <memory>
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
|
||||
class Image
|
||||
: public EnableSharedFromThis<Image>,
|
||||
private NonCopyable {
|
||||
public:
|
||||
|
||||
using byte_type = unsigned char;
|
||||
|
||||
static SharedPtr<Image> FromBuffer(Buffer buffer);
|
||||
|
||||
Image();
|
||||
|
||||
Image(Image &&rhs);
|
||||
Image &operator=(Image &&rhs);
|
||||
|
||||
void Clear();
|
||||
|
||||
size_t GetFrameNumber() const {
|
||||
return _frame_number;
|
||||
}
|
||||
|
||||
size_t GetWidth() const {
|
||||
return _width;
|
||||
}
|
||||
|
||||
size_t GetHeight() const {
|
||||
return _height;
|
||||
}
|
||||
|
||||
const std::string &GetType() const {
|
||||
return _type;
|
||||
}
|
||||
|
||||
float GetFOV() const {
|
||||
return _fov;
|
||||
}
|
||||
|
||||
byte_type *GetData() {
|
||||
return _raw_data.get();
|
||||
}
|
||||
|
||||
const byte_type *GetData() const {
|
||||
return _raw_data.get();
|
||||
}
|
||||
|
||||
size_t GetSize() const {
|
||||
return 4u * _width * _height;
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
size_t _frame_number;
|
||||
|
||||
size_t _width;
|
||||
|
||||
size_t _height;
|
||||
|
||||
std::string _type;
|
||||
|
||||
float _fov;
|
||||
|
||||
std::unique_ptr<byte_type[]> _raw_data;
|
||||
};
|
||||
|
||||
} // namespace client
|
||||
} // namespace carla
|
|
@ -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/client/Sensor.h"
|
||||
|
||||
#include "carla/Logging.h"
|
||||
#include "carla/client/detail/Client.h"
|
||||
|
||||
#include <exception>
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
|
||||
Sensor::~Sensor() {
|
||||
if (IsAlive()) {
|
||||
log_warning(
|
||||
"sensor object went out of the scope but the sensor is still alive",
|
||||
"in the simulation:",
|
||||
GetDisplayId());
|
||||
}
|
||||
if (_is_listening) {
|
||||
try {
|
||||
Stop();
|
||||
} catch (const std::exception &e) {
|
||||
log_error("excetion trying to stop sensor:", GetDisplayId(), ':', e.what());
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void Sensor::Listen(CallbackFunctionType callback) {
|
||||
log_debug(GetDisplayId(), ": subscribing to stream");
|
||||
if (_is_listening) {
|
||||
log_warning(
|
||||
"attempting to listen to stream but sensor is already listening:",
|
||||
GetDisplayId());
|
||||
return;
|
||||
}
|
||||
GetEpisode()->SubscribeToStream(
|
||||
GetActorDescription().GetStreamToken(),
|
||||
std::move(callback));
|
||||
_is_listening = true;
|
||||
}
|
||||
|
||||
void Sensor::Stop() {
|
||||
if (!_is_listening) {
|
||||
log_warning(
|
||||
"attempting to unsubscribe from stream but sensor wasn't listening:",
|
||||
GetDisplayId());
|
||||
return;
|
||||
}
|
||||
GetEpisode()->UnSubscribeFromStream(
|
||||
GetActorDescription().GetStreamToken());
|
||||
_is_listening = false;
|
||||
}
|
||||
|
||||
void Sensor::Destroy() {
|
||||
if (_is_listening) {
|
||||
Stop();
|
||||
}
|
||||
Actor::Destroy();
|
||||
}
|
||||
|
||||
} // namespace client
|
||||
} // namespace carla
|
|
@ -6,31 +6,36 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "carla/Logging.h"
|
||||
#include "carla/client/Actor.h"
|
||||
|
||||
#include <functional>
|
||||
|
||||
namespace carla {
|
||||
namespace sensor { class SensorData; }
|
||||
namespace client {
|
||||
|
||||
class Sensor : public Actor {
|
||||
public:
|
||||
|
||||
template <typename Functor>
|
||||
void Listen(Functor callback) {
|
||||
/// @todo should we check if we are already listening?
|
||||
log_debug("sensor", GetId(), "type", GetTypeId(), ": subscribing to stream");
|
||||
GetWorld()->GetClient().SubscribeToStream(_stream_token, std::forward<Functor>(callback));
|
||||
explicit Sensor(ActorInitializer init) : Actor(std::move(init)) {}
|
||||
|
||||
~Sensor();
|
||||
|
||||
using CallbackFunctionType = std::function<void(SharedPtr<sensor::SensorData>)>;
|
||||
|
||||
void Listen(CallbackFunctionType callback);
|
||||
|
||||
void Stop();
|
||||
|
||||
bool IsListening() const {
|
||||
return _is_listening;
|
||||
}
|
||||
|
||||
void Destroy() override;
|
||||
|
||||
private:
|
||||
|
||||
friend class Client;
|
||||
|
||||
Sensor(carla::rpc::Actor actor, SharedPtr<World> world)
|
||||
: Actor(actor, std::move(world)),
|
||||
_stream_token(actor.GetStreamToken()) {}
|
||||
|
||||
streaming::Token _stream_token;
|
||||
bool _is_listening = false;
|
||||
};
|
||||
|
||||
} // namespace client
|
||||
|
|
|
@ -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>.
|
||||
|
||||
#include "carla/client/Vehicle.h"
|
||||
#include "carla/client/detail/Client.h"
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
|
||||
void Vehicle::ApplyControl(const Control &control) {
|
||||
if (control != _control) {
|
||||
GetEpisode()->ApplyControlToVehicle(*this, control);
|
||||
_control = control;
|
||||
}
|
||||
}
|
||||
|
||||
void Vehicle::SetAutopilot(bool enabled) {
|
||||
GetEpisode()->SetVehicleAutopilot(*this, enabled);
|
||||
}
|
||||
|
||||
} // namespace client
|
||||
} // namespace carla
|
|
@ -7,7 +7,7 @@
|
|||
#pragma once
|
||||
|
||||
#include "carla/client/Actor.h"
|
||||
#include "carla/client/Control.h"
|
||||
#include "carla/rpc/VehicleControl.h"
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
|
@ -15,20 +15,21 @@ namespace client {
|
|||
class Vehicle : public Actor {
|
||||
public:
|
||||
|
||||
void ApplyControl(const VehicleControl &control) {
|
||||
GetWorld()->GetClient().ApplyControlToActor(*this, control);
|
||||
}
|
||||
using Control = rpc::VehicleControl;
|
||||
|
||||
void SetAutopilot(bool enabled = true) {
|
||||
GetWorld()->GetClient().SetActorAutopilot(*this, enabled);
|
||||
explicit Vehicle(ActorInitializer init) : Actor(std::move(init)) {}
|
||||
|
||||
void SetAutopilot(bool enabled = true);
|
||||
|
||||
void ApplyControl(const Control &control);
|
||||
|
||||
const Control &GetControl() const {
|
||||
return _control;
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
friend class Client;
|
||||
|
||||
template <typename ... Args>
|
||||
Vehicle(Args && ... args) : Actor(std::forward<Args>(args)...) {}
|
||||
Control _control;
|
||||
};
|
||||
|
||||
} // namespace client
|
||||
|
|
|
@ -7,20 +7,42 @@
|
|||
#include "carla/client/World.h"
|
||||
|
||||
#include "carla/Logging.h"
|
||||
#include "carla/client/Actor.h"
|
||||
#include "carla/client/ActorBlueprint.h"
|
||||
#include "carla/client/detail/Client.h"
|
||||
|
||||
#include <rpc/rpc_error.h>
|
||||
#include <exception>
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
|
||||
SharedPtr<BlueprintLibrary> World::GetBlueprintLibrary() const {
|
||||
return _episode->GetBlueprintLibrary();
|
||||
}
|
||||
|
||||
SharedPtr<Actor> World::GetSpectator() const {
|
||||
return _episode->GetSpectator();
|
||||
}
|
||||
|
||||
SharedPtr<Actor> World::SpawnActor(
|
||||
const ActorBlueprint &blueprint,
|
||||
const geom::Transform &transform,
|
||||
Actor *parent_actor) {
|
||||
try {
|
||||
return _episode->SpawnActor(blueprint, transform, parent_actor);
|
||||
} catch (const std::exception &e) {
|
||||
log_warning("SpawnActor: failed with:", e.what());
|
||||
throw;
|
||||
}
|
||||
}
|
||||
|
||||
SharedPtr<Actor> World::TrySpawnActor(
|
||||
const ActorBlueprint &blueprint,
|
||||
const Transform &transform,
|
||||
Actor *parent) {
|
||||
const geom::Transform &transform,
|
||||
Actor *parent_actor) {
|
||||
try {
|
||||
return SpawnActor(blueprint, transform, parent);
|
||||
} catch (const ::rpc::rpc_error &e) {
|
||||
log_warning("TrySpawnActor: failed with:", e.what());
|
||||
return SpawnActor(blueprint, transform, parent_actor);
|
||||
} catch (const std::exception &) {
|
||||
return nullptr;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -6,56 +6,45 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "carla/Debug.h"
|
||||
#include "carla/NonCopyable.h"
|
||||
#include "carla/client/Client.h"
|
||||
#include "carla/client/Memory.h"
|
||||
#include "carla/Memory.h"
|
||||
#include "carla/client/detail/Episode.h"
|
||||
#include "carla/geom/Transform.h"
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
|
||||
class Actor;
|
||||
class ActorBlueprint;
|
||||
class BlueprintLibrary;
|
||||
|
||||
class World
|
||||
: public EnableSharedFromThis<World>,
|
||||
private NonCopyable {
|
||||
class World {
|
||||
public:
|
||||
|
||||
SharedPtr<BlueprintLibrary> GetBlueprintLibrary() const {
|
||||
return _parent->GetBlueprintLibrary();
|
||||
}
|
||||
World(detail::Episode episode) : _episode(std::move(episode)) {}
|
||||
|
||||
SharedPtr<Actor> GetSpectator() const {
|
||||
return _parent->GetSpectator();
|
||||
}
|
||||
World(const World &) = default;
|
||||
World(World &&) = default;
|
||||
|
||||
SharedPtr<Actor> TrySpawnActor(
|
||||
const ActorBlueprint &blueprint,
|
||||
const Transform &transform,
|
||||
Actor *parent = nullptr);
|
||||
World &operator=(const World &) = default;
|
||||
World &operator=(World &&) = default;
|
||||
|
||||
SharedPtr<BlueprintLibrary> GetBlueprintLibrary() const;
|
||||
|
||||
SharedPtr<Actor> GetSpectator() const;
|
||||
|
||||
SharedPtr<Actor> SpawnActor(
|
||||
const ActorBlueprint &blueprint,
|
||||
const Transform &transform,
|
||||
Actor *parent = nullptr) {
|
||||
return _parent->SpawnActor(blueprint, transform, parent);
|
||||
}
|
||||
const geom::Transform &transform,
|
||||
Actor *parent = nullptr);
|
||||
|
||||
Client &GetClient() const {
|
||||
DEBUG_ASSERT(_parent != nullptr);
|
||||
return *_parent;
|
||||
}
|
||||
SharedPtr<Actor> TrySpawnActor(
|
||||
const ActorBlueprint &blueprint,
|
||||
const geom::Transform &transform,
|
||||
Actor *parent = nullptr);
|
||||
|
||||
private:
|
||||
|
||||
friend class Client;
|
||||
|
||||
explicit World(SharedPtr<Client> parent)
|
||||
: _parent(std::move(parent)) {
|
||||
DEBUG_ASSERT(_parent != nullptr);
|
||||
}
|
||||
|
||||
SharedPtr<Client> _parent;
|
||||
detail::Episode _episode;
|
||||
};
|
||||
|
||||
} // namespace client
|
||||
|
|
|
@ -0,0 +1,86 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "carla/client/detail/ActorFactory.h"
|
||||
|
||||
#include "carla/Logging.h"
|
||||
#include "carla/StringUtil.h"
|
||||
#include "carla/client/Actor.h"
|
||||
#include "carla/client/Sensor.h"
|
||||
#include "carla/client/Vehicle.h"
|
||||
#include "carla/client/World.h"
|
||||
#include "carla/client/detail/Client.h"
|
||||
|
||||
#include <rpc/config.h>
|
||||
#include <rpc/rpc_error.h>
|
||||
|
||||
#include <exception>
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
namespace detail {
|
||||
|
||||
// A deleter cannot throw exceptions; and unlike std::unique_ptr, the deleter
|
||||
// of (std|boost)::shared_ptr is invoked even if the managed pointer is null.
|
||||
struct GarbageCollector {
|
||||
void operator()(::carla::client::Actor *ptr) const noexcept {
|
||||
if ((ptr != nullptr) && ptr->IsAlive()) {
|
||||
try {
|
||||
ptr->Destroy();
|
||||
delete ptr;
|
||||
} catch (const ::rpc::timeout &timeout) {
|
||||
log_error(timeout.what());
|
||||
log_error(
|
||||
"timeout while trying to garbage collect Actor",
|
||||
ptr->GetDisplayId(),
|
||||
"actor hasn't been removed from the simulation");
|
||||
} catch (const std::exception &e) {
|
||||
log_critical(
|
||||
"exception thrown while trying to garbage collect Actor",
|
||||
ptr->GetDisplayId(),
|
||||
e.what());
|
||||
throw; // calls terminate.
|
||||
} catch (...) {
|
||||
log_critical(
|
||||
"unknown exception thrown while trying to garbage collect an Actor :",
|
||||
ptr->GetDisplayId());
|
||||
throw; // calls terminate.
|
||||
}
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
template <typename ActorT>
|
||||
static auto MakeActorImpl(ActorInitializer init, GarbageCollectionPolicy gc) {
|
||||
log_debug(
|
||||
init.GetDisplayId(),
|
||||
"created",
|
||||
gc == GarbageCollectionPolicy::Enabled ? "with" : "without",
|
||||
"garbage collection");
|
||||
if (gc == GarbageCollectionPolicy::Enabled) {
|
||||
return SharedPtr<ActorT>{new ActorT(std::move(init)), GarbageCollector()};
|
||||
}
|
||||
DEBUG_ASSERT(gc == GarbageCollectionPolicy::Disabled);
|
||||
return SharedPtr<ActorT>{new ActorT(std::move(init))};
|
||||
}
|
||||
|
||||
SharedPtr<Actor> ActorFactory::MakeActor(
|
||||
Episode episode,
|
||||
rpc::Actor description,
|
||||
GarbageCollectionPolicy gc) {
|
||||
const auto gcw = episode->GetGarbageCollectionPolicy();
|
||||
const auto gca = (gc == GarbageCollectionPolicy::Inherit ? gcw : gc);
|
||||
if (description.HasAStream()) {
|
||||
return MakeActorImpl<Sensor>(ActorInitializer{description, episode}, gca);
|
||||
} else if (StringUtil::StartsWith(description.description.id, "vehicle.")) {
|
||||
return MakeActorImpl<Vehicle>(ActorInitializer{description, episode}, gca);
|
||||
}
|
||||
return MakeActorImpl<Actor>(ActorInitializer{description, episode}, gca);
|
||||
}
|
||||
|
||||
} // namespace detail
|
||||
} // namespace client
|
||||
} // namespace carla
|
|
@ -0,0 +1,32 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "carla/Memory.h"
|
||||
#include "carla/client/GarbageCollectionPolicy.h"
|
||||
#include "carla/client/detail/Episode.h"
|
||||
#include "carla/rpc/Actor.h"
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
|
||||
class Actor;
|
||||
|
||||
namespace detail {
|
||||
|
||||
class ActorFactory {
|
||||
public:
|
||||
|
||||
static SharedPtr<Actor> MakeActor(
|
||||
Episode episode,
|
||||
rpc::Actor actor_description,
|
||||
GarbageCollectionPolicy gc = GarbageCollectionPolicy::Inherit);
|
||||
};
|
||||
|
||||
} // namespace detail
|
||||
} // namespace client
|
||||
} // namespace carla
|
|
@ -0,0 +1,28 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "carla/client/detail/ActorState.h"
|
||||
|
||||
#include <string>
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
namespace detail {
|
||||
|
||||
ActorState::ActorState(rpc::Actor description, Episode episode)
|
||||
: _description(std::move(description)),
|
||||
_episode(std::move(episode)),
|
||||
_display_id([](const auto &desc) {
|
||||
using namespace std::string_literals;
|
||||
return
|
||||
"Actor "s +
|
||||
std::to_string(desc.id) +
|
||||
" (" + desc.description.id + ')';
|
||||
}(_description)) {}
|
||||
|
||||
} // namespace detail
|
||||
} // namespace client
|
||||
} // namespace carla
|
|
@ -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>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "carla/NonCopyable.h"
|
||||
#include "carla/client/World.h"
|
||||
#include "carla/rpc/Actor.h"
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
namespace detail {
|
||||
|
||||
class ActorFactory;
|
||||
|
||||
class ActorState : private MovableNonCopyable {
|
||||
public:
|
||||
|
||||
auto GetId() const {
|
||||
return _description.id;
|
||||
}
|
||||
|
||||
const std::string &GetTypeId() const {
|
||||
return _description.description.id;
|
||||
}
|
||||
|
||||
const std::string &GetDisplayId() const {
|
||||
return _display_id;
|
||||
}
|
||||
|
||||
World GetWorld() const {
|
||||
return _episode;
|
||||
}
|
||||
|
||||
protected:
|
||||
|
||||
const rpc::Actor &GetActorDescription() const {
|
||||
return _description;
|
||||
}
|
||||
|
||||
Episode &GetEpisode() {
|
||||
return _episode;
|
||||
}
|
||||
|
||||
const Episode &GetEpisode() const {
|
||||
return _episode;
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
friend class detail::Client;
|
||||
|
||||
ActorState(rpc::Actor description, Episode episode);
|
||||
|
||||
rpc::Actor _description;
|
||||
|
||||
Episode _episode;
|
||||
|
||||
std::string _display_id;
|
||||
};
|
||||
|
||||
} // namespace detail
|
||||
|
||||
class ActorInitializer : public detail::ActorState {
|
||||
public:
|
||||
ActorInitializer(ActorInitializer &&) = default;
|
||||
private:
|
||||
friend class detail::ActorFactory;
|
||||
using detail::ActorState::ActorState;
|
||||
};
|
||||
|
||||
} // namespace client
|
||||
} // namespace carla
|
|
@ -0,0 +1,173 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "carla/client/detail/Client.h"
|
||||
|
||||
#include "carla/Version.h"
|
||||
#include "carla/client/Actor.h"
|
||||
#include "carla/client/BlueprintLibrary.h"
|
||||
#include "carla/client/Vehicle.h"
|
||||
#include "carla/client/World.h"
|
||||
#include "carla/client/detail/ActorFactory.h"
|
||||
#include "carla/client/detail/Episode.h"
|
||||
#include "carla/rpc/Client.h"
|
||||
#include "carla/sensor/Deserializer.h"
|
||||
#include "carla/streaming/Client.h"
|
||||
|
||||
#include <thread>
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
namespace detail {
|
||||
|
||||
// ===========================================================================
|
||||
// -- Client::Pimpl ----------------------------------------------------------
|
||||
// ===========================================================================
|
||||
|
||||
class Client::Pimpl {
|
||||
public:
|
||||
|
||||
Pimpl(const std::string &host, uint16_t port, size_t worker_threads)
|
||||
: rpc_client(host, port),
|
||||
streaming_client(host) {
|
||||
streaming_client.AsyncRun(
|
||||
worker_threads > 0u ? worker_threads : std::thread::hardware_concurrency());
|
||||
}
|
||||
|
||||
template <typename T, typename... Args>
|
||||
T CallAndWait(const std::string &function, Args &&... args) {
|
||||
return rpc_client.call(function, std::forward<Args>(args)...).template as<T>();
|
||||
}
|
||||
|
||||
template <typename... Args>
|
||||
void AsyncCall(const std::string &function, Args &&... args) {
|
||||
// Discard returned future.
|
||||
rpc_client.async_call(function, std::forward<Args>(args)...);
|
||||
}
|
||||
|
||||
rpc::Client rpc_client;
|
||||
|
||||
streaming::Client streaming_client;
|
||||
};
|
||||
|
||||
// ===========================================================================
|
||||
// -- Client -----------------------------------------------------------------
|
||||
// ===========================================================================
|
||||
|
||||
Client::Client(
|
||||
const std::string &host,
|
||||
const uint16_t port,
|
||||
const size_t worker_threads,
|
||||
const bool enable_garbage_collection)
|
||||
: LIBCARLA_INITIALIZE_LIFETIME_PROFILER("carla::client::detail::Client"),
|
||||
_pimpl(std::make_unique<Pimpl>(host, port, worker_threads)),
|
||||
_gc_policy(enable_garbage_collection ?
|
||||
GarbageCollectionPolicy::Enabled : GarbageCollectionPolicy::Disabled) {}
|
||||
|
||||
Client::~Client() = default;
|
||||
|
||||
void Client::SetTimeout(time_duration timeout) {
|
||||
_pimpl->rpc_client.set_timeout(timeout.milliseconds());
|
||||
}
|
||||
|
||||
// Keep this function in the cpp, to avoid recompiling everything on each
|
||||
// commit.
|
||||
std::string Client::GetClientVersion() {
|
||||
return ::carla::version();
|
||||
}
|
||||
|
||||
std::string Client::GetServerVersion() {
|
||||
return _pimpl->CallAndWait<std::string>("version");
|
||||
}
|
||||
|
||||
bool Client::Ping() {
|
||||
return _pimpl->CallAndWait<bool>("ping");
|
||||
}
|
||||
|
||||
SharedPtr<BlueprintLibrary> Client::GetBlueprintLibrary() {
|
||||
using return_type = std::vector<carla::rpc::ActorDefinition>;
|
||||
auto result = _pimpl->CallAndWait<return_type>("get_actor_definitions");
|
||||
return MakeShared<BlueprintLibrary>(result);
|
||||
}
|
||||
|
||||
SharedPtr<Actor> Client::GetSpectator() {
|
||||
auto spectator = _pimpl->CallAndWait<carla::rpc::Actor>("get_spectator");
|
||||
return ActorFactory::MakeActor(
|
||||
GetCurrentEpisode(),
|
||||
spectator,
|
||||
GarbageCollectionPolicy::Disabled);
|
||||
}
|
||||
|
||||
SharedPtr<Actor> Client::SpawnActor(
|
||||
const ActorBlueprint &blueprint,
|
||||
const geom::Transform &transform,
|
||||
Actor *parent,
|
||||
GarbageCollectionPolicy gc) {
|
||||
rpc::Actor actor;
|
||||
if (parent != nullptr) {
|
||||
actor = _pimpl->CallAndWait<rpc::Actor>("spawn_actor_with_parent",
|
||||
transform,
|
||||
blueprint.MakeActorDescription(),
|
||||
parent->Serialize());
|
||||
} else {
|
||||
actor = _pimpl->CallAndWait<rpc::Actor>("spawn_actor",
|
||||
transform,
|
||||
blueprint.MakeActorDescription());
|
||||
}
|
||||
return ActorFactory::MakeActor(GetCurrentEpisode(), actor, gc);
|
||||
}
|
||||
|
||||
bool Client::DestroyActor(Actor &actor) {
|
||||
auto result = _pimpl->CallAndWait<bool>("destroy_actor", actor.Serialize());
|
||||
// Remove it's persistent state so it cannot access the client anymore.
|
||||
actor.GetEpisode().ClearState();
|
||||
log_debug(actor.GetDisplayId(), "destroyed.");
|
||||
return result;
|
||||
}
|
||||
|
||||
void Client::SubscribeToStream(
|
||||
const streaming::Token &token,
|
||||
std::function<void(SharedPtr<sensor::SensorData>)> callback) {
|
||||
_pimpl->streaming_client.Subscribe(token, [callback](auto buffer) {
|
||||
callback(sensor::Deserializer::Deserialize(std::move(buffer)));
|
||||
});
|
||||
}
|
||||
|
||||
void Client::UnSubscribeFromStream(const streaming::Token &token) {
|
||||
_pimpl->streaming_client.UnSubscribe(token);
|
||||
}
|
||||
|
||||
geom::Location Client::GetActorLocation(const Actor &actor) {
|
||||
return _pimpl->CallAndWait<geom::Location>("get_actor_location", actor.Serialize());
|
||||
}
|
||||
|
||||
geom::Transform Client::GetActorTransform(const Actor &actor) {
|
||||
return _pimpl->CallAndWait<geom::Transform>("get_actor_transform", actor.Serialize());
|
||||
}
|
||||
|
||||
void Client::SetActorLocation(Actor &actor, const geom::Location &location) {
|
||||
_pimpl->AsyncCall("set_actor_location", actor.Serialize(), location);
|
||||
}
|
||||
|
||||
void Client::SetActorTransform(Actor &actor, const geom::Transform &transform) {
|
||||
_pimpl->AsyncCall("set_actor_transform", actor.Serialize(), transform);
|
||||
}
|
||||
|
||||
void Client::SetVehicleAutopilot(
|
||||
Vehicle &vehicle,
|
||||
const bool enabled) {
|
||||
_pimpl->AsyncCall("set_actor_autopilot", vehicle.Serialize(), enabled);
|
||||
}
|
||||
|
||||
void Client::ApplyControlToVehicle(
|
||||
Vehicle &vehicle,
|
||||
const rpc::VehicleControl &control) {
|
||||
_pimpl->AsyncCall("apply_control_to_actor", vehicle.Serialize(), control);
|
||||
}
|
||||
|
||||
} // namespace detail
|
||||
} // namespace client
|
||||
} // namespace carla
|
|
@ -0,0 +1,118 @@
|
|||
// 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/Memory.h"
|
||||
#include "carla/NonCopyable.h"
|
||||
#include "carla/Time.h"
|
||||
#include "carla/client/GarbageCollectionPolicy.h"
|
||||
#include "carla/client/detail/Episode.h"
|
||||
#include "carla/geom/Transform.h"
|
||||
#include "carla/profiler/LifetimeProfiled.h"
|
||||
|
||||
#include <functional>
|
||||
#include <memory>
|
||||
#include <string>
|
||||
|
||||
// Forward declarations.
|
||||
namespace carla {
|
||||
namespace client {
|
||||
class Actor;
|
||||
class ActorBlueprint;
|
||||
class BlueprintLibrary;
|
||||
class Vehicle;
|
||||
class Episode;
|
||||
}
|
||||
namespace rpc { class VehicleControl; }
|
||||
namespace sensor { class SensorData; }
|
||||
namespace streaming { class Token; }
|
||||
}
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
namespace detail {
|
||||
|
||||
/// @todo Make sure this class is really thread-safe.
|
||||
class Client
|
||||
: public EnableSharedFromThis<Client>,
|
||||
private profiler::LifetimeProfiled,
|
||||
private NonCopyable {
|
||||
public:
|
||||
|
||||
explicit Client(
|
||||
const std::string &host,
|
||||
uint16_t port,
|
||||
size_t worker_threads = 0u,
|
||||
bool enable_garbage_collection = false);
|
||||
|
||||
~Client();
|
||||
|
||||
void SetTimeout(time_duration timeout);
|
||||
|
||||
std::string GetClientVersion();
|
||||
|
||||
std::string GetServerVersion();
|
||||
|
||||
bool Ping();
|
||||
|
||||
SharedPtr<BlueprintLibrary> GetBlueprintLibrary();
|
||||
|
||||
SharedPtr<Actor> GetSpectator();
|
||||
|
||||
SharedPtr<Actor> SpawnActor(
|
||||
const ActorBlueprint &blueprint,
|
||||
const geom::Transform &transform,
|
||||
Actor *parent,
|
||||
GarbageCollectionPolicy gc = GarbageCollectionPolicy::Inherit);
|
||||
|
||||
bool DestroyActor(Actor &actor);
|
||||
|
||||
void SubscribeToStream(
|
||||
const streaming::Token &token,
|
||||
std::function<void(SharedPtr<sensor::SensorData>)> callback);
|
||||
|
||||
void UnSubscribeFromStream(const streaming::Token &token);
|
||||
|
||||
geom::Location GetActorLocation(const Actor &actor);
|
||||
|
||||
geom::Transform GetActorTransform(const Actor &actor);
|
||||
|
||||
void SetActorLocation(Actor &actor, const geom::Location &location);
|
||||
|
||||
void SetActorTransform(Actor &actor, const geom::Transform &transform);
|
||||
|
||||
void SetVehicleAutopilot(Vehicle &vehicle, bool enabled = true);
|
||||
|
||||
void ApplyControlToVehicle(Vehicle &vehicle, const rpc::VehicleControl &control);
|
||||
|
||||
GarbageCollectionPolicy GetGarbageCollectionPolicy() const {
|
||||
return _gc_policy;
|
||||
}
|
||||
|
||||
size_t GetCurrentEpisodeId() const {
|
||||
return _episode_id;
|
||||
}
|
||||
|
||||
Episode GetCurrentEpisode() {
|
||||
return shared_from_this();
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
class Pimpl;
|
||||
const std::unique_ptr<Pimpl> _pimpl;
|
||||
|
||||
const GarbageCollectionPolicy _gc_policy;
|
||||
|
||||
// At this point the id won't change because we cannot yet restart the
|
||||
// episode from the client.
|
||||
const size_t _episode_id = 0u;
|
||||
};
|
||||
|
||||
} // namespace detail
|
||||
} // namespace client
|
||||
} // namespace carla
|
|
@ -0,0 +1,44 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "carla/client/detail/Episode.h"
|
||||
|
||||
#include "carla/client/detail/Client.h"
|
||||
|
||||
#include <boost/atomic.hpp>
|
||||
|
||||
#include <exception>
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
namespace detail {
|
||||
|
||||
EpisodeImpl::EpisodeImpl(SharedPtr<PersistentState> state)
|
||||
: _state(std::move(state)),
|
||||
_episode_id(_state->GetCurrentEpisodeId()) {}
|
||||
|
||||
void EpisodeImpl::ClearState() {
|
||||
boost::atomic_store_explicit(&_state, {nullptr}, boost::memory_order_relaxed);
|
||||
}
|
||||
|
||||
PersistentState &EpisodeImpl::GetPersistentStateWithChecks() const {
|
||||
auto state = boost::atomic_load_explicit(&_state, boost::memory_order_relaxed);
|
||||
if (state == nullptr) {
|
||||
throw std::runtime_error(
|
||||
"trying to operate on a destroyed actor; an actor's function "
|
||||
"was called, but the actor is already destroyed.");
|
||||
}
|
||||
if (_episode_id != _state->GetCurrentEpisodeId()) {
|
||||
throw std::runtime_error(
|
||||
"trying to access an expired episode; a new episode was started "
|
||||
"in the simulation but an object tried accessing the old one.");
|
||||
}
|
||||
return *_state;
|
||||
}
|
||||
|
||||
} // namespace detail
|
||||
} // namespace client
|
||||
} // namespace carla
|
|
@ -0,0 +1,58 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "carla/Debug.h"
|
||||
#include "carla/Memory.h"
|
||||
#include "carla/client/detail/PersistentState.h"
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
namespace detail {
|
||||
|
||||
class EpisodeImpl {
|
||||
public:
|
||||
|
||||
PersistentState &operator*() const {
|
||||
return GetPersistentStateWithChecks();
|
||||
}
|
||||
|
||||
PersistentState *operator->() const {
|
||||
return &GetPersistentStateWithChecks();
|
||||
}
|
||||
|
||||
protected:
|
||||
|
||||
EpisodeImpl(SharedPtr<PersistentState> state);
|
||||
|
||||
void ClearState();
|
||||
|
||||
private:
|
||||
|
||||
PersistentState &GetPersistentStateWithChecks() const;
|
||||
|
||||
SharedPtr<PersistentState> _state;
|
||||
|
||||
size_t _episode_id;
|
||||
};
|
||||
|
||||
class Episode : private EpisodeImpl {
|
||||
public:
|
||||
|
||||
using EpisodeImpl::operator*;
|
||||
using EpisodeImpl::operator->;
|
||||
|
||||
private:
|
||||
|
||||
friend PersistentState;
|
||||
|
||||
using EpisodeImpl::EpisodeImpl;
|
||||
};
|
||||
|
||||
} // namespace detail
|
||||
} // namespace client
|
||||
} // namespace carla
|
|
@ -0,0 +1,23 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
// #include "carla/client/detail/Client.h"
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
namespace detail {
|
||||
|
||||
class Client;
|
||||
|
||||
/// At this point the client is the only persistent state we have, but
|
||||
/// conceptually is nice to make the distinction.
|
||||
using PersistentState = Client;
|
||||
|
||||
} // namespace detail
|
||||
} // namespace client
|
||||
} // namespace carla
|
|
@ -0,0 +1,91 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "carla/MsgPack.h"
|
||||
|
||||
#ifdef LIBCARLA_INCLUDED_FROM_UE4
|
||||
# include "Math/Vector.h"
|
||||
#endif // LIBCARLA_INCLUDED_FROM_UE4
|
||||
|
||||
namespace carla {
|
||||
namespace geom {
|
||||
|
||||
class Location {
|
||||
public:
|
||||
|
||||
float x = 0.0f;
|
||||
float y = 0.0f;
|
||||
float z = 0.0f;
|
||||
|
||||
Location() = default;
|
||||
|
||||
Location(float ix, float iy, float iz)
|
||||
: x(ix),
|
||||
y(iy),
|
||||
z(iz) {}
|
||||
|
||||
Location &operator+=(const Location &rhs) {
|
||||
x += rhs.x;
|
||||
y += rhs.y;
|
||||
z += rhs.z;
|
||||
return *this;
|
||||
}
|
||||
|
||||
friend Location operator+(Location lhs, const Location &rhs) {
|
||||
lhs += rhs;
|
||||
return lhs;
|
||||
}
|
||||
|
||||
Location &operator-=(const Location &rhs) {
|
||||
x -= rhs.x;
|
||||
y -= rhs.y;
|
||||
z -= rhs.z;
|
||||
return *this;
|
||||
}
|
||||
|
||||
friend Location operator-(Location lhs, const Location &rhs) {
|
||||
lhs -= rhs;
|
||||
return lhs;
|
||||
}
|
||||
|
||||
#ifdef LIBCARLA_INCLUDED_FROM_UE4
|
||||
|
||||
Location(const FVector &vector) // from centimeters to meters.
|
||||
: Location(1e-2f * vector.X, 1e-2f * vector.Y, 1e-2f * vector.Z) {}
|
||||
|
||||
operator FVector() const {
|
||||
return FVector{1e2f * x, 1e2f * y, 1e2f * z}; // from meters to centimeters.
|
||||
}
|
||||
|
||||
#endif // LIBCARLA_INCLUDED_FROM_UE4
|
||||
|
||||
// =========================================================================
|
||||
/// @todo The following is copy-pasted from MSGPACK_DEFINE_ARRAY.
|
||||
/// This is a workaround for an issue in msgpack library. The
|
||||
/// MSGPACK_DEFINE_ARRAY macro is shadowing our `z` variable.
|
||||
/// https://github.com/msgpack/msgpack-c/issues/709
|
||||
// =========================================================================
|
||||
template <typename Packer>
|
||||
void msgpack_pack(Packer& pk) const
|
||||
{
|
||||
clmdep_msgpack::type::make_define_array(x, y, z).msgpack_pack(pk);
|
||||
}
|
||||
void msgpack_unpack(clmdep_msgpack::object const& o)
|
||||
{
|
||||
clmdep_msgpack::type::make_define_array(x, y, z).msgpack_unpack(o);
|
||||
}
|
||||
template <typename MSGPACK_OBJECT>
|
||||
void msgpack_object(MSGPACK_OBJECT* o, clmdep_msgpack::zone& sneaky_variable_that_shadows_z) const
|
||||
{
|
||||
clmdep_msgpack::type::make_define_array(x, y, z).msgpack_object(o, sneaky_variable_that_shadows_z);
|
||||
}
|
||||
// =========================================================================
|
||||
};
|
||||
|
||||
} // namespace geom
|
||||
} // namespace carla
|
|
@ -0,0 +1,75 @@
|
|||
// 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/MsgPack.h"
|
||||
#include "carla/geom/Location.h"
|
||||
|
||||
#ifdef LIBCARLA_INCLUDED_FROM_UE4
|
||||
# include "Transform.h"
|
||||
#endif // LIBCARLA_INCLUDED_FROM_UE4
|
||||
|
||||
namespace carla {
|
||||
namespace geom {
|
||||
|
||||
class Rotation {
|
||||
public:
|
||||
|
||||
Rotation() = default;
|
||||
|
||||
Rotation(float p, float y, float r)
|
||||
: pitch(p),
|
||||
yaw(y),
|
||||
roll(r) {}
|
||||
|
||||
float pitch = 0.0f;
|
||||
float yaw = 0.0f;
|
||||
float roll = 0.0f;
|
||||
|
||||
#ifdef LIBCARLA_INCLUDED_FROM_UE4
|
||||
|
||||
Rotation(const FRotator &rotator)
|
||||
: Rotation(rotator.Pitch, rotator.Yaw, rotator.Roll) {}
|
||||
|
||||
operator FRotator() const {
|
||||
return FRotator{pitch, yaw, roll};
|
||||
}
|
||||
|
||||
#endif // LIBCARLA_INCLUDED_FROM_UE4
|
||||
|
||||
MSGPACK_DEFINE_ARRAY(pitch, yaw, roll);
|
||||
};
|
||||
|
||||
class Transform {
|
||||
public:
|
||||
|
||||
Transform() = default;
|
||||
|
||||
Transform(const Location &in_location, const Rotation &in_rotation)
|
||||
: location(in_location),
|
||||
rotation(in_rotation) {}
|
||||
|
||||
Location location;
|
||||
Rotation rotation;
|
||||
|
||||
#ifdef LIBCARLA_INCLUDED_FROM_UE4
|
||||
|
||||
Transform(const FTransform &transform)
|
||||
: Transform(Location(transform.GetLocation()), Rotation(transform.Rotator())) {}
|
||||
|
||||
operator FTransform() const {
|
||||
const FVector scale{1.0f, 1.0f, 1.0f};
|
||||
return FTransform{FRotator(rotation), FVector(location), scale};
|
||||
}
|
||||
|
||||
#endif // LIBCARLA_INCLUDED_FROM_UE4
|
||||
|
||||
MSGPACK_DEFINE_ARRAY(location, rotation);
|
||||
};
|
||||
|
||||
} // namespace geom
|
||||
} // namespace carla
|
|
@ -0,0 +1,20 @@
|
|||
// 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
|
||||
|
||||
#if defined(__clang__)
|
||||
# pragma clang diagnostic push
|
||||
# pragma clang diagnostic ignored "-Wc++11-narrowing"
|
||||
# pragma clang diagnostic ignored "-Wunused-parameter"
|
||||
# pragma clang diagnostic ignored "-Wunused-local-typedef"
|
||||
#endif
|
||||
|
||||
#include <boost/gil/gil_all.hpp>
|
||||
|
||||
#if defined(__clang__)
|
||||
# pragma clang diagnostic pop
|
||||
#endif
|
|
@ -0,0 +1,74 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <cstdint>
|
||||
|
||||
namespace carla {
|
||||
namespace image {
|
||||
namespace detail {
|
||||
|
||||
static constexpr
|
||||
#if __cplusplus >= 201703L // C++17
|
||||
inline
|
||||
#endif
|
||||
uint8_t CITYSCAPES_PALETTE_MAP[][3u] = {
|
||||
{ 0u, 0u, 0u}, // unlabeled = 0u,
|
||||
{ 70u, 70u, 70u}, // building = 1u,
|
||||
{190u, 153u, 153u}, // fence = 2u,
|
||||
{250u, 170u, 160u}, // other = 3u,
|
||||
{220u, 20u, 60u}, // pedestrian = 4u,
|
||||
{153u, 153u, 153u}, // pole = 5u,
|
||||
{153u, 153u, 153u}, // road line = 6u,
|
||||
{128u, 64u, 128u}, // road = 7u,
|
||||
{244u, 35u, 232u}, // sidewalk = 8u,
|
||||
{107u, 142u, 35u}, // vegetation = 9u,
|
||||
{ 0u, 0u, 142u}, // car = 10u,
|
||||
{102u, 102u, 156u}, // wall = 11u,
|
||||
{220u, 220u, 0u}, // traffic sign = 12u,
|
||||
// { 0u, 0u, 70u}, // truck
|
||||
// { 0u, 0u, 90u}, // caravan
|
||||
// { 0u, 0u, 110u}, // trailer
|
||||
// { 0u, 0u, 142u}, // license plate
|
||||
// { 0u, 0u, 230u}, // motorcycle
|
||||
// { 0u, 60u, 100u}, // bus
|
||||
// { 0u, 80u, 100u}, // train
|
||||
// { 70u, 130u, 180u}, // sky
|
||||
// { 81u, 0u, 81u}, // ground
|
||||
// {111u, 74u, 0u}, // dynamic
|
||||
// {119u, 11u, 32u}, // bicycle
|
||||
// {150u, 100u, 100u}, // bridge
|
||||
// {150u, 120u, 90u}, // tunnel
|
||||
// {152u, 251u, 152u}, // terrain
|
||||
// {153u, 153u, 153u}, // polegroup
|
||||
// {180u, 165u, 180u}, // guard rail
|
||||
// {230u, 150u, 140u}, // rail track
|
||||
// {250u, 170u, 30u}, // traffic light
|
||||
// {250u, 170u, 160u}, // parking
|
||||
// {255u, 0u, 0u}, // rider
|
||||
};
|
||||
|
||||
} // namespace detail
|
||||
|
||||
class CityScapesPalette {
|
||||
public:
|
||||
|
||||
static constexpr auto GetNumberOfTags() {
|
||||
return sizeof(detail::CITYSCAPES_PALETTE_MAP) /
|
||||
sizeof(*detail::CITYSCAPES_PALETTE_MAP);
|
||||
}
|
||||
|
||||
/// Return an RGB uint8_t array.
|
||||
///
|
||||
/// @warning It overflows if @a tag is greater than GetNumberOfTags().
|
||||
static constexpr auto GetColor(uint8_t tag) {
|
||||
return detail::CITYSCAPES_PALETTE_MAP[tag % GetNumberOfTags()];
|
||||
}
|
||||
};
|
||||
|
||||
} // namespace image
|
||||
} // namespace carla
|
|
@ -0,0 +1,60 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "carla/image/BoostGil.h"
|
||||
#include "carla/image/CityScapesPalette.h"
|
||||
|
||||
namespace carla {
|
||||
namespace image {
|
||||
|
||||
class ColorConverter {
|
||||
public:
|
||||
|
||||
struct LogarithmicLinear {
|
||||
template <typename DstPixelT>
|
||||
void operator()(const boost::gil::gray32fc_pixel_t &src, DstPixelT &dst) const {
|
||||
using namespace boost::gil;
|
||||
const float value = 1.0f + std::log(src[0u]) / 5.70378f;
|
||||
const float clamped = std::max(std::min(value, 1.0f), 0.005f);
|
||||
color_convert(gray32fc_pixel_t{clamped}, dst);
|
||||
}
|
||||
};
|
||||
|
||||
struct Depth {
|
||||
template <typename SrcPixelT, typename DstPixelT>
|
||||
void operator()(const SrcPixelT &src, DstPixelT &dst) const {
|
||||
using namespace boost::gil;
|
||||
static_assert(
|
||||
sizeof(typename color_space_type<SrcPixelT>::type) == sizeof(uint8_t),
|
||||
"Invalid pixel type.");
|
||||
const float depth =
|
||||
get_color(src, red_t()) +
|
||||
(get_color(src, green_t()) * 256) +
|
||||
(get_color(src, blue_t()) * 256 * 256);
|
||||
const float normalized = depth / static_cast<float>(256 * 256 * 256 - 1);
|
||||
color_convert(gray32fc_pixel_t{normalized}, dst);
|
||||
}
|
||||
};
|
||||
|
||||
struct LogarithmicDepth {};
|
||||
|
||||
struct CityScapesPalette {
|
||||
template <typename SrcPixelT, typename DstPixelT>
|
||||
void operator()(const SrcPixelT &src, DstPixelT &dst) const {
|
||||
using namespace boost::gil;
|
||||
static_assert(
|
||||
sizeof(typename color_space_type<SrcPixelT>::type) == sizeof(uint8_t),
|
||||
"Invalid pixel type.");
|
||||
const auto color = image::CityScapesPalette::GetColor(get_color(src, red_t()));
|
||||
color_convert(rgb8c_pixel_t{color[0u], color[1u], color[2u]}, dst);
|
||||
}
|
||||
};
|
||||
};
|
||||
|
||||
} // namespace image
|
||||
} // namespace carla
|
|
@ -0,0 +1,34 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "carla/image/ImageView.h"
|
||||
|
||||
namespace carla {
|
||||
namespace image {
|
||||
|
||||
class ImageConverter {
|
||||
public:
|
||||
|
||||
template <typename SrcViewT, typename DstViewT>
|
||||
static void CopyPixels(const SrcViewT &src, DstViewT &dst) {
|
||||
boost::gil::copy_pixels(src, dst);
|
||||
}
|
||||
|
||||
template <typename ColorConverter, typename MutableImageView>
|
||||
static void ConvertInPlace(
|
||||
MutableImageView &image_view,
|
||||
ColorConverter converter = ColorConverter()) {
|
||||
using DstPixelT = typename MutableImageView::value_type;
|
||||
CopyPixels(
|
||||
ImageView::MakeColorConvertedView<MutableImageView, DstPixelT>(image_view, converter),
|
||||
image_view);
|
||||
}
|
||||
};
|
||||
|
||||
} // namespace image
|
||||
} // namespace carla
|
|
@ -0,0 +1,30 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "carla/image/ImageIOConfig.h"
|
||||
|
||||
namespace carla {
|
||||
namespace image {
|
||||
|
||||
class ImageIO {
|
||||
public:
|
||||
|
||||
template <typename ImageT, typename IO = io::any>
|
||||
static void ReadImage(const std::string &in_filename, ImageT &image, IO = IO()) {
|
||||
IO::read_image(in_filename, image);
|
||||
}
|
||||
|
||||
template <typename ViewT, typename IO = io::any>
|
||||
static std::string WriteView(std::string out_filename, const ViewT &image_view, IO = IO()) {
|
||||
IO::write_view(out_filename, image_view);
|
||||
return out_filename;
|
||||
}
|
||||
};
|
||||
|
||||
} // namespace image
|
||||
} // namespace carla
|
|
@ -0,0 +1,326 @@
|
|||
// 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/FileSystem.h"
|
||||
#include "carla/Logging.h"
|
||||
#include "carla/StringUtil.h"
|
||||
#include "carla/image/BoostGil.h"
|
||||
|
||||
#ifndef LIBCARLA_IMAGE_WITH_PNG_SUPPORT
|
||||
# if defined(__has_include) && __has_include("png.h")
|
||||
# define LIBCARLA_IMAGE_WITH_PNG_SUPPORT true
|
||||
# else
|
||||
# define LIBCARLA_IMAGE_WITH_PNG_SUPPORT false
|
||||
# endif
|
||||
#endif
|
||||
|
||||
#ifndef LIBCARLA_IMAGE_WITH_JPEG_SUPPORT
|
||||
# if defined(__has_include) && __has_include("jpeglib.h")
|
||||
# define LIBCARLA_IMAGE_WITH_JPEG_SUPPORT true
|
||||
# else
|
||||
# define LIBCARLA_IMAGE_WITH_JPEG_SUPPORT false
|
||||
# endif
|
||||
#endif
|
||||
|
||||
#ifndef LIBCARLA_IMAGE_WITH_TIFF_SUPPORT
|
||||
# if defined(__has_include) && __has_include("tiffio.h")
|
||||
# define LIBCARLA_IMAGE_WITH_TIFF_SUPPORT true
|
||||
# else
|
||||
# define LIBCARLA_IMAGE_WITH_TIFF_SUPPORT false
|
||||
# endif
|
||||
#endif
|
||||
|
||||
#if defined(__clang__)
|
||||
# pragma clang diagnostic push
|
||||
# pragma clang diagnostic ignored "-Wunused-parameter"
|
||||
#endif
|
||||
|
||||
#if LIBCARLA_IMAGE_WITH_PNG_SUPPORT == true
|
||||
# ifndef png_infopp_NULL
|
||||
# define png_infopp_NULL (png_infopp)NULL
|
||||
# endif // png_infopp_NULL
|
||||
# ifndef int_p_NULL
|
||||
# define int_p_NULL (int*)NULL
|
||||
# endif // int_p_NULL
|
||||
# include <boost/gil/extension/io/png_io.hpp>
|
||||
#endif
|
||||
|
||||
#if LIBCARLA_IMAGE_WITH_JPEG_SUPPORT == true
|
||||
# include <boost/gil/extension/io/jpeg_io.hpp>
|
||||
#endif
|
||||
|
||||
#if LIBCARLA_IMAGE_WITH_TIFF_SUPPORT == true
|
||||
# include <boost/gil/extension/io/tiff_io.hpp>
|
||||
#endif
|
||||
|
||||
#if defined(__clang__)
|
||||
# pragma clang diagnostic pop
|
||||
#endif
|
||||
|
||||
namespace carla {
|
||||
namespace image {
|
||||
namespace io {
|
||||
|
||||
constexpr bool has_png_support() {
|
||||
return LIBCARLA_IMAGE_WITH_PNG_SUPPORT;
|
||||
}
|
||||
|
||||
constexpr bool has_jpeg_support() {
|
||||
return LIBCARLA_IMAGE_WITH_JPEG_SUPPORT;
|
||||
}
|
||||
|
||||
constexpr bool has_tiff_support() {
|
||||
return LIBCARLA_IMAGE_WITH_TIFF_SUPPORT;
|
||||
}
|
||||
|
||||
static_assert(has_png_support() || has_jpeg_support() || has_tiff_support(),
|
||||
"No image format supported, please compile with at least one of "
|
||||
"LIBCARLA_IMAGE_WITH_PNG_SUPPORT, LIBCARLA_IMAGE_WITH_JPEG_SUPPORT, "
|
||||
"or LIBCARLA_IMAGE_WITH_TIFF_SUPPORT");
|
||||
|
||||
namespace detail {
|
||||
|
||||
struct io_png {
|
||||
|
||||
static constexpr bool is_supported = has_png_support();
|
||||
|
||||
#if LIBCARLA_IMAGE_WITH_PNG_SUPPORT
|
||||
|
||||
static constexpr const char *get_default_extension() {
|
||||
return "png";
|
||||
}
|
||||
|
||||
template <typename Str>
|
||||
static bool match_extension(const Str &str) {
|
||||
return StringUtil::EndsWith(str, get_default_extension());
|
||||
}
|
||||
|
||||
template <typename Str, typename ImageT>
|
||||
static void read_image(Str &&in_filename, ImageT &image) {
|
||||
boost::gil::png_read_and_convert_image(std::forward<Str>(in_filename), image);
|
||||
}
|
||||
|
||||
template <typename Str, typename ViewT>
|
||||
static void write_view(Str &&out_filename, const ViewT &view) {
|
||||
boost::gil::png_write_view(std::forward<Str>(out_filename), view);
|
||||
}
|
||||
|
||||
#endif // LIBCARLA_IMAGE_WITH_PNG_SUPPORT
|
||||
};
|
||||
|
||||
struct io_jpeg {
|
||||
|
||||
static constexpr bool is_supported = has_jpeg_support();
|
||||
|
||||
#if LIBCARLA_IMAGE_WITH_JPEG_SUPPORT
|
||||
|
||||
static constexpr const char *get_default_extension() {
|
||||
return "jpeg";
|
||||
}
|
||||
|
||||
template <typename Str>
|
||||
static bool match_extension(const Str &str) {
|
||||
return StringUtil::EndsWith(str, get_default_extension()) ||
|
||||
StringUtil::EndsWith(str, "jpg");
|
||||
}
|
||||
|
||||
template <typename Str, typename ImageT>
|
||||
static void read_image(Str &&in_filename, ImageT &image) {
|
||||
boost::gil::jpeg_read_image(std::forward<Str>(in_filename), image);
|
||||
}
|
||||
|
||||
template <typename Str, typename ViewT>
|
||||
static typename std::enable_if<boost::gil::jpeg_write_support<ViewT>::is_supported>::type
|
||||
write_view(Str &&out_filename, const ViewT &view) {
|
||||
using namespace boost::gil;
|
||||
jpeg_write_view(std::forward<Str>(out_filename), view);
|
||||
}
|
||||
|
||||
template <typename Str, typename ViewT>
|
||||
static typename std::enable_if<!boost::gil::jpeg_write_support<ViewT>::is_supported>::type
|
||||
write_view(Str &&out_filename, const ViewT &view) {
|
||||
using namespace boost::gil;
|
||||
jpeg_write_view(std::forward<Str>(out_filename), color_converted_view<rgb8_pixel_t>(view));
|
||||
}
|
||||
|
||||
#endif // LIBCARLA_IMAGE_WITH_JPEG_SUPPORT
|
||||
};
|
||||
|
||||
struct io_tiff {
|
||||
|
||||
static constexpr bool is_supported = has_tiff_support();
|
||||
|
||||
#if LIBCARLA_IMAGE_WITH_TIFF_SUPPORT
|
||||
|
||||
static constexpr const char *get_default_extension() {
|
||||
return "tiff";
|
||||
}
|
||||
|
||||
template <typename Str>
|
||||
static bool match_extension(const Str &str) {
|
||||
return StringUtil::EndsWith(str, get_default_extension());
|
||||
}
|
||||
|
||||
template <typename Str, typename ImageT>
|
||||
static void read_image(Str &&in_filename, ImageT &image) {
|
||||
boost::gil::tiff_read_and_convert_image(std::forward<Str>(in_filename), image);
|
||||
}
|
||||
|
||||
template <typename Str, typename ViewT>
|
||||
static typename std::enable_if<boost::gil::tiff_write_support<ViewT>::is_supported>::type
|
||||
write_view(Str &&out_filename, const ViewT &view) {
|
||||
using namespace boost::gil;
|
||||
tiff_write_view(std::forward<Str>(out_filename), view);
|
||||
}
|
||||
|
||||
template <typename Str, typename ViewT>
|
||||
static typename std::enable_if<!boost::gil::tiff_write_support<ViewT>::is_supported>::type
|
||||
write_view(Str &&out_filename, const ViewT &view) {
|
||||
using namespace boost::gil;
|
||||
tiff_write_view(std::forward<Str>(out_filename), color_converted_view<rgb8_pixel_t>(view));
|
||||
}
|
||||
|
||||
#endif // LIBCARLA_IMAGE_WITH_TIFF_SUPPORT
|
||||
};
|
||||
|
||||
struct io_resolver {
|
||||
|
||||
template <typename IO, typename Str>
|
||||
static typename std::enable_if<IO::is_supported, bool>::type match_extension(const Str &str) {
|
||||
return IO::match_extension(str);
|
||||
}
|
||||
|
||||
template <typename IO, typename Str>
|
||||
static typename std::enable_if<!IO::is_supported, bool>::type match_extension(const Str &) {
|
||||
return false;
|
||||
}
|
||||
|
||||
template <typename IO, typename Str, typename... Args>
|
||||
static typename std::enable_if<IO::is_supported>::type read_image(const Str &path, Args &&... args) {
|
||||
log_debug("reading", path, "as", IO::get_default_extension());
|
||||
IO::read_image(path, std::forward<Args>(args)...);
|
||||
}
|
||||
|
||||
template <typename IO, typename... Args>
|
||||
static typename std::enable_if<!IO::is_supported>::type read_image(Args &&...) {
|
||||
DEBUG_ASSERT(false);
|
||||
}
|
||||
|
||||
template <typename IO, typename... Args>
|
||||
static typename std::enable_if<IO::is_supported>::type write_view(std::string &path, Args &&... args) {
|
||||
FileSystem::ValidateFilePath(path, IO::get_default_extension());
|
||||
log_debug("writing", path, "as", IO::get_default_extension());
|
||||
IO::write_view(path, std::forward<Args>(args)...);
|
||||
}
|
||||
|
||||
template <typename IO, typename... Args>
|
||||
static typename std::enable_if<!IO::is_supported>::type write_view(Args &&...) {
|
||||
DEBUG_ASSERT(false);
|
||||
}
|
||||
};
|
||||
|
||||
template <typename... IOs>
|
||||
struct io_impl;
|
||||
|
||||
template <typename IO>
|
||||
struct io_impl<IO> {
|
||||
constexpr static bool is_supported = IO::is_supported;
|
||||
|
||||
template <typename... Args>
|
||||
static void read_image(Args &&... args) {
|
||||
io_resolver::read_image<IO>(std::forward<Args>(args)...);
|
||||
}
|
||||
|
||||
template <typename... Args>
|
||||
static void write_view(Args &&... args) {
|
||||
io_resolver::write_view<IO>(std::forward<Args>(args)...);
|
||||
}
|
||||
|
||||
template <typename Str, typename... Args>
|
||||
static bool try_read_image(const Str &filename, Args &&... args) {
|
||||
if (io_resolver::match_extension<IO>(filename)) {
|
||||
io_resolver::read_image<IO>(filename, std::forward<Args>(args)...);
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
template <typename Str, typename... Args>
|
||||
static bool try_write_view(Str &filename, Args &&... args) {
|
||||
if (io_resolver::match_extension<IO>(filename)) {
|
||||
io_resolver::write_view<IO>(filename, std::forward<Args>(args)...);
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
};
|
||||
|
||||
template <typename IO, typename... IOs>
|
||||
struct io_impl<IO, IOs...> {
|
||||
private:
|
||||
using self = io_impl<IO>;
|
||||
using recursive = io_impl<IOs...>;
|
||||
public:
|
||||
|
||||
constexpr static bool is_supported = self::is_supported || recursive::is_supported;
|
||||
|
||||
template <typename... Args>
|
||||
static void read_image(Args &... args) {
|
||||
if (!recursive::try_read_image(args...)) {
|
||||
self::read_image(args...);
|
||||
}
|
||||
}
|
||||
|
||||
template <typename... Args>
|
||||
static bool try_read_image(Args &... args) {
|
||||
return recursive::try_read_image(args...) || self::try_read_image(args...);
|
||||
}
|
||||
|
||||
template <typename... Args>
|
||||
static void write_view(Args &... args) {
|
||||
if (!recursive::try_write_view(args...)) {
|
||||
self::write_view(args...);
|
||||
}
|
||||
}
|
||||
|
||||
template <typename... Args>
|
||||
static bool try_write_view(Args &... args) {
|
||||
return recursive::try_write_view(args...) || self::try_write_view(args...);
|
||||
}
|
||||
};
|
||||
|
||||
template <typename DefaultIO, typename... IOs>
|
||||
struct io_any : detail::io_impl<DefaultIO, IOs...> {
|
||||
static_assert(DefaultIO::is_supported, "Default IO needs to be supported.");
|
||||
};
|
||||
|
||||
} // namespace detail
|
||||
|
||||
struct png : detail::io_impl<detail::io_png> {};
|
||||
|
||||
struct jpeg : detail::io_impl<detail::io_jpeg> {};
|
||||
|
||||
struct tiff : detail::io_impl<detail::io_tiff> {};
|
||||
|
||||
#if LIBCARLA_IMAGE_WITH_PNG_SUPPORT
|
||||
|
||||
struct any : detail::io_any<detail::io_png, detail::io_tiff, detail::io_jpeg> {};
|
||||
|
||||
#elif LIBCARLA_IMAGE_WITH_TIFF_SUPPORT
|
||||
|
||||
struct any : detail::io_any<detail::io_tiff, detail::io_jpeg> {};
|
||||
|
||||
#else // Then for sure this one is available.
|
||||
|
||||
struct any : detail::io_any<detail::io_jpeg> {};
|
||||
|
||||
#endif
|
||||
|
||||
} // namespace io
|
||||
} // namespace image
|
||||
} // namespace carla
|
|
@ -0,0 +1,98 @@
|
|||
// 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/image/BoostGil.h"
|
||||
#include "carla/image/ColorConverter.h"
|
||||
#include "carla/sensor/data/Color.h"
|
||||
#include "carla/sensor/data/ImageTmpl.h"
|
||||
|
||||
#include <type_traits>
|
||||
|
||||
namespace carla {
|
||||
namespace image {
|
||||
|
||||
class ImageView {
|
||||
private:
|
||||
public:
|
||||
|
||||
template <typename SrcViewT>
|
||||
using GrayPixelLayout = boost::gil::pixel<typename boost::gil::channel_type<SrcViewT>::type, boost::gil::gray_layout_t>;
|
||||
|
||||
template <typename DstPixelT, typename ImageT>
|
||||
static auto MakeViewFromSensorImage(ImageT &image) {
|
||||
using namespace boost::gil;
|
||||
namespace sd = carla::sensor::data;
|
||||
static_assert(
|
||||
std::is_same<typename ImageT::pixel_type, sd::Color>::value,
|
||||
"Invalid pixel type");
|
||||
static_assert(
|
||||
sizeof(sd::Color) == sizeof(DstPixelT),
|
||||
"Invalid pixel size");
|
||||
return interleaved_view(
|
||||
image.GetWidth(),
|
||||
image.GetHeight(),
|
||||
reinterpret_cast<DstPixelT*>(image.data()),
|
||||
sizeof(sd::Color) * image.GetWidth()); // row length in bytes.
|
||||
}
|
||||
|
||||
public:
|
||||
|
||||
template <typename ImageT>
|
||||
static auto MakeView(ImageT &image) {
|
||||
return boost::gil::view(image);
|
||||
}
|
||||
|
||||
static auto MakeView(sensor::data::ImageTmpl<sensor::data::Color> &image) {
|
||||
return MakeViewFromSensorImage<boost::gil::bgra8_pixel_t>(image);
|
||||
}
|
||||
|
||||
static auto MakeView(const sensor::data::ImageTmpl<sensor::data::Color> &image) {
|
||||
return MakeViewFromSensorImage<boost::gil::bgra8c_pixel_t>(image);
|
||||
}
|
||||
|
||||
template <typename SrcViewT, typename DstPixelT, typename CC>
|
||||
static auto MakeColorConvertedView(const SrcViewT &src, CC cc) {
|
||||
return _MakeColorConvertedView<DstPixelT>(src, cc);
|
||||
}
|
||||
|
||||
template <typename SrcViewT, typename DstPixelT = GrayPixelLayout<SrcViewT>>
|
||||
static auto MakeColorConvertedView(const SrcViewT &src, ColorConverter::Depth cc) {
|
||||
return _MakeColorConvertedView<DstPixelT>(src, cc);
|
||||
}
|
||||
|
||||
template <typename SrcViewT, typename DstPixelT = GrayPixelLayout<SrcViewT>>
|
||||
static auto MakeColorConvertedView(const SrcViewT &src, ColorConverter::LogarithmicDepth) {
|
||||
auto intermediate_view = _MakeColorConvertedView<boost::gil::gray32f_pixel_t>(src, ColorConverter::Depth());
|
||||
return _MakeColorConvertedView<DstPixelT>(intermediate_view, ColorConverter::LogarithmicLinear());
|
||||
}
|
||||
|
||||
template <typename SrcViewT, typename DstPixelT = typename SrcViewT::value_type>
|
||||
static auto MakeColorConvertedView(const SrcViewT &src, ColorConverter::CityScapesPalette cc) {
|
||||
return _MakeColorConvertedView<DstPixelT>(src, cc);
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
template <typename SrcView, typename DstP, typename CC>
|
||||
struct color_converted_type {
|
||||
private:
|
||||
typedef boost::gil::color_convert_deref_fn<typename SrcView::const_t::reference, DstP, CC> deref_t;
|
||||
typedef typename SrcView::template add_deref<deref_t> add_ref_t;
|
||||
public:
|
||||
typedef typename add_ref_t::type type;
|
||||
static type make(const SrcView &sv, CC cc) { return add_ref_t::make(sv, deref_t(cc)); }
|
||||
};
|
||||
|
||||
template <typename DstPixelT, typename SrcViewT, typename CC>
|
||||
static auto _MakeColorConvertedView(const SrcViewT &src, CC cc) {
|
||||
return color_converted_type<SrcViewT, DstPixelT, CC>::make(src, cc);
|
||||
}
|
||||
};
|
||||
|
||||
} // namespace image
|
||||
} // namespace carla
|
|
@ -0,0 +1,26 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "carla/road/Map.h"
|
||||
|
||||
#include <istream>
|
||||
#include <ostream>
|
||||
|
||||
namespace carla {
|
||||
namespace opendrive {
|
||||
|
||||
class OpenDrive {
|
||||
public:
|
||||
|
||||
static road::Map Load(std::istream &input);
|
||||
|
||||
static void Dump(const road::Map &map, std::ostream &output);
|
||||
};
|
||||
|
||||
} // namespace opendrive
|
||||
} // namespace carla
|
|
@ -0,0 +1,29 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "carla/pointcloud/PointCloudIO.h"
|
||||
|
||||
#include <iomanip>
|
||||
|
||||
namespace carla {
|
||||
namespace pointcloud {
|
||||
|
||||
void PointCloudIO::WriteHeader(std::ostream &out, size_t number_of_points) {
|
||||
out << "ply\n"
|
||||
"format ascii 1.0\n"
|
||||
"element vertex " << number_of_points << "\n"
|
||||
"property float32 x\n"
|
||||
"property float32 y\n"
|
||||
"property float32 z\n"
|
||||
// "property uchar diffuse_red\n"
|
||||
// "property uchar diffuse_green\n"
|
||||
// "property uchar diffuse_blue\n"
|
||||
"end_header\n";
|
||||
out << std::fixed << std::setprecision(4u);
|
||||
}
|
||||
|
||||
} // namespace pointcloud
|
||||
} // namespace carla
|
|
@ -0,0 +1,42 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "carla/FileSystem.h"
|
||||
|
||||
#include <fstream>
|
||||
#include <iterator>
|
||||
|
||||
namespace carla {
|
||||
namespace pointcloud {
|
||||
|
||||
class PointCloudIO {
|
||||
public:
|
||||
|
||||
template <typename PointIt>
|
||||
static void Dump(std::ostream &out, PointIt begin, PointIt end) {
|
||||
WriteHeader(out, std::distance(begin, end));
|
||||
for (; begin != end; ++begin) {
|
||||
out << begin->x << ' ' << begin->y << ' ' << begin->z << '\n';
|
||||
}
|
||||
}
|
||||
|
||||
template <typename PointIt>
|
||||
static std::string SaveToDisk(std::string path, PointIt begin, PointIt end) {
|
||||
FileSystem::ValidateFilePath(path, ".ply");
|
||||
std::ofstream out(path);
|
||||
Dump(out, begin, end);
|
||||
return path;
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
static void WriteHeader(std::ostream &out, size_t number_of_points);
|
||||
};
|
||||
|
||||
} // namespace pointcloud
|
||||
} // namespace carla
|
|
@ -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>.
|
||||
|
||||
#ifndef LIBCARLA_ENABLE_LIFETIME_PROFILER
|
||||
# define LIBCARLA_ENABLE_LIFETIME_PROFILER
|
||||
#endif // LIBCARLA_ENABLE_LIFETIME_PROFILER
|
||||
|
||||
#include "carla/Debug.h"
|
||||
#include "carla/Logging.h"
|
||||
#include "carla/profiler/LifetimeProfiled.h"
|
||||
|
||||
#include <mutex>
|
||||
#include <unordered_map>
|
||||
|
||||
namespace carla {
|
||||
namespace profiler {
|
||||
|
||||
template <typename ... Args>
|
||||
static inline void log(Args && ... args) {
|
||||
logging::write_to_stream(std::cerr, "LIFETIME:", std::forward<Args>(args) ..., '\n');
|
||||
}
|
||||
|
||||
class LifetimeProfiler {
|
||||
public:
|
||||
|
||||
~LifetimeProfiler() {
|
||||
std::lock_guard<std::mutex> lock(_mutex);
|
||||
if (!_objects.empty()) {
|
||||
log("WARNING! the following objects were not destructed.");
|
||||
for (const auto &item : _objects) {
|
||||
log(item.second, "still alive.");
|
||||
}
|
||||
DEBUG_ERROR;
|
||||
}
|
||||
}
|
||||
|
||||
void Register(void *object, std::string display_name) {
|
||||
#if LIBCARLA_LOG_LEVEL <= LIBCARLA_LOG_LEVEL_DEBUG
|
||||
log('+', display_name);
|
||||
#endif
|
||||
std::lock_guard<std::mutex> lock(_mutex);
|
||||
_objects.emplace(object, std::move(display_name));
|
||||
}
|
||||
|
||||
void Deregister(void *object) {
|
||||
std::lock_guard<std::mutex> lock(_mutex);
|
||||
auto it = _objects.find(object);
|
||||
DEBUG_ASSERT(it != _objects.end());
|
||||
#if LIBCARLA_LOG_LEVEL <= LIBCARLA_LOG_LEVEL_DEBUG
|
||||
log('-', it->second);
|
||||
#endif
|
||||
_objects.erase(it);
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
std::mutex _mutex;
|
||||
|
||||
std::unordered_map<void *, std::string> _objects;
|
||||
};
|
||||
|
||||
static LifetimeProfiler PROFILER;
|
||||
|
||||
LifetimeProfiled::LifetimeProfiled(std::string display_name) {
|
||||
PROFILER.Register(this, std::move(display_name));
|
||||
}
|
||||
|
||||
LifetimeProfiled::~LifetimeProfiled() {
|
||||
PROFILER.Deregister(this);
|
||||
}
|
||||
|
||||
} // namespace profiler
|
||||
} // namespace carla
|
|
@ -0,0 +1,39 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <string>
|
||||
|
||||
namespace carla {
|
||||
namespace profiler {
|
||||
|
||||
class LifetimeProfiled {
|
||||
protected:
|
||||
|
||||
#ifndef LIBCARLA_ENABLE_LIFETIME_PROFILER
|
||||
|
||||
LifetimeProfiled() = default;
|
||||
|
||||
#else
|
||||
|
||||
LifetimeProfiled(std::string display_name);
|
||||
|
||||
public:
|
||||
|
||||
~LifetimeProfiled();
|
||||
|
||||
#endif // LIBCARLA_ENABLE_LIFETIME_PROFILER
|
||||
};
|
||||
|
||||
} // namespace profiler
|
||||
} // namespace carla
|
||||
|
||||
#ifndef LIBCARLA_ENABLE_LIFETIME_PROFILER
|
||||
# define LIBCARLA_INITIALIZE_LIFETIME_PROFILER(display_name) ::carla::profiler::LifetimeProfiled()
|
||||
#else
|
||||
# define LIBCARLA_INITIALIZE_LIFETIME_PROFILER(display_name) ::carla::profiler::LifetimeProfiled(display_name)
|
||||
#endif // LIBCARLA_ENABLE_LIFETIME_PROFILER
|
|
@ -6,14 +6,14 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "carla/rpc/Transform.h"
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
namespace road {
|
||||
|
||||
using Location = carla::rpc::Location;
|
||||
using Rotation = carla::rpc::Rotation;
|
||||
using Transform = carla::rpc::Transform;
|
||||
class Map {
|
||||
public:
|
||||
|
||||
} // namespace client
|
||||
|
||||
};
|
||||
|
||||
} // namespace road
|
||||
} // namespace carla
|
|
@ -6,13 +6,16 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
class FSensorDataView;
|
||||
namespace carla {
|
||||
namespace road {
|
||||
|
||||
/// Interface for sensor data sinks.
|
||||
class ISensorDataSink {
|
||||
public:
|
||||
class MapBuilder {
|
||||
public:
|
||||
|
||||
virtual ~ISensorDataSink() {}
|
||||
|
||||
virtual void Write(const FSensorDataView &SensorData) = 0;
|
||||
};
|
||||
|
||||
|
||||
};
|
||||
|
||||
} // namespace road
|
||||
} // namespace carla
|
|
@ -32,12 +32,12 @@ namespace rpc {
|
|||
|
||||
std::vector<unsigned char> stream_token;
|
||||
|
||||
bool IsASensor() const {
|
||||
bool HasAStream() const {
|
||||
return stream_token.size() == sizeof(streaming::Token::data);
|
||||
}
|
||||
|
||||
streaming::Token GetStreamToken() const {
|
||||
DEBUG_ASSERT(IsASensor());
|
||||
DEBUG_ASSERT(HasAStream());
|
||||
streaming::Token token;
|
||||
std::memcpy(&token.data[0u], stream_token.data(), stream_token.size());
|
||||
return token;
|
||||
|
|
|
@ -6,8 +6,8 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "carla/MsgPack.h"
|
||||
#include "carla/rpc/ActorAttributeType.h"
|
||||
#include "carla/rpc/MsgPack.h"
|
||||
#include "carla/rpc/String.h"
|
||||
|
||||
#include <vector>
|
||||
|
|
|
@ -6,8 +6,8 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "carla/MsgPack.h"
|
||||
#include "carla/rpc/ActorAttribute.h"
|
||||
#include "carla/rpc/MsgPack.h"
|
||||
#include "carla/rpc/String.h"
|
||||
|
||||
#include <vector>
|
||||
|
|
|
@ -6,8 +6,8 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "carla/MsgPack.h"
|
||||
#include "carla/rpc/ActorAttribute.h"
|
||||
#include "carla/rpc/MsgPack.h"
|
||||
#include "carla/rpc/String.h"
|
||||
|
||||
#include <vector>
|
||||
|
|
|
@ -6,86 +6,12 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "carla/rpc/MsgPack.h"
|
||||
|
||||
#ifdef LIBCARLA_INCLUDED_FROM_UE4
|
||||
# include "Math/Vector.h"
|
||||
#endif // LIBCARLA_INCLUDED_FROM_UE4
|
||||
#include "carla/geom/Location.h"
|
||||
|
||||
namespace carla {
|
||||
namespace rpc {
|
||||
|
||||
class Location {
|
||||
public:
|
||||
|
||||
float x = 0.0f;
|
||||
float y = 0.0f;
|
||||
float z = 0.0f;
|
||||
|
||||
Location() = default;
|
||||
|
||||
Location(float ix, float iy, float iz)
|
||||
: x(ix),
|
||||
y(iy),
|
||||
z(iz) {}
|
||||
|
||||
Location &operator+=(const Location &rhs) {
|
||||
x += rhs.x;
|
||||
y += rhs.y;
|
||||
z += rhs.z;
|
||||
return *this;
|
||||
}
|
||||
|
||||
friend Location operator+(Location lhs, const Location &rhs) {
|
||||
lhs += rhs;
|
||||
return lhs;
|
||||
}
|
||||
|
||||
Location &operator-=(const Location &rhs) {
|
||||
x -= rhs.x;
|
||||
y -= rhs.y;
|
||||
z -= rhs.z;
|
||||
return *this;
|
||||
}
|
||||
|
||||
friend Location operator-(Location lhs, const Location &rhs) {
|
||||
lhs -= rhs;
|
||||
return lhs;
|
||||
}
|
||||
|
||||
#ifdef LIBCARLA_INCLUDED_FROM_UE4
|
||||
|
||||
Location(const FVector &vector) // from centimeters to meters.
|
||||
: Location(1e-2f * vector.X, 1e-2f * vector.Y, 1e-2f * vector.Z) {}
|
||||
|
||||
operator FVector() const {
|
||||
return FVector{1e2f * x, 1e2f * y, 1e2f * z}; // from meters to centimeters.
|
||||
}
|
||||
|
||||
#endif // LIBCARLA_INCLUDED_FROM_UE4
|
||||
|
||||
// =========================================================================
|
||||
/// @todo The following is copy-pasted from MSGPACK_DEFINE_ARRAY.
|
||||
/// This is a workaround for an issue in msgpack library. The
|
||||
/// MSGPACK_DEFINE_ARRAY macro is shadowing our `z` variable.
|
||||
/// https://github.com/msgpack/msgpack-c/issues/709
|
||||
// =========================================================================
|
||||
template <typename Packer>
|
||||
void msgpack_pack(Packer& pk) const
|
||||
{
|
||||
clmdep_msgpack::type::make_define_array(x, y, z).msgpack_pack(pk);
|
||||
}
|
||||
void msgpack_unpack(clmdep_msgpack::object const& o)
|
||||
{
|
||||
clmdep_msgpack::type::make_define_array(x, y, z).msgpack_unpack(o);
|
||||
}
|
||||
template <typename MSGPACK_OBJECT>
|
||||
void msgpack_object(MSGPACK_OBJECT* o, clmdep_msgpack::zone& sneaky_variable_that_shadows_z) const
|
||||
{
|
||||
clmdep_msgpack::type::make_define_array(x, y, z).msgpack_object(o, sneaky_variable_that_shadows_z);
|
||||
}
|
||||
// =========================================================================
|
||||
};
|
||||
using Location = geom::Location;
|
||||
|
||||
} // namespace rpc
|
||||
} // namespace carla
|
||||
|
|
|
@ -6,70 +6,14 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "carla/rpc/Location.h"
|
||||
#include "carla/rpc/MsgPack.h"
|
||||
|
||||
#ifdef LIBCARLA_INCLUDED_FROM_UE4
|
||||
# include "Transform.h"
|
||||
#endif // LIBCARLA_INCLUDED_FROM_UE4
|
||||
#include "carla/geom/Transform.h"
|
||||
|
||||
namespace carla {
|
||||
namespace rpc {
|
||||
|
||||
class Rotation {
|
||||
public:
|
||||
using Rotation = geom::Rotation;
|
||||
|
||||
Rotation() = default;
|
||||
|
||||
Rotation(float p, float y, float r)
|
||||
: pitch(p),
|
||||
yaw(y),
|
||||
roll(r) {}
|
||||
|
||||
float pitch = 0.0f;
|
||||
float yaw = 0.0f;
|
||||
float roll = 0.0f;
|
||||
|
||||
#ifdef LIBCARLA_INCLUDED_FROM_UE4
|
||||
|
||||
Rotation(const FRotator &rotator)
|
||||
: Rotation(rotator.Pitch, rotator.Yaw, rotator.Roll) {}
|
||||
|
||||
operator FRotator() const {
|
||||
return FRotator{pitch, yaw, roll};
|
||||
}
|
||||
|
||||
#endif // LIBCARLA_INCLUDED_FROM_UE4
|
||||
|
||||
MSGPACK_DEFINE_ARRAY(pitch, yaw, roll);
|
||||
};
|
||||
|
||||
class Transform {
|
||||
public:
|
||||
|
||||
Transform() = default;
|
||||
|
||||
Transform(const Location &in_location, const Rotation &in_rotation)
|
||||
: location(in_location),
|
||||
rotation(in_rotation) {}
|
||||
|
||||
Location location;
|
||||
Rotation rotation;
|
||||
|
||||
#ifdef LIBCARLA_INCLUDED_FROM_UE4
|
||||
|
||||
Transform(const FTransform &transform)
|
||||
: Transform(Location(transform.GetLocation()), Rotation(transform.Rotator())) {}
|
||||
|
||||
operator FTransform() const {
|
||||
const FVector scale{1.0f, 1.0f, 1.0f};
|
||||
return FTransform{FRotator(rotation), FVector(location), scale};
|
||||
}
|
||||
|
||||
#endif // LIBCARLA_INCLUDED_FROM_UE4
|
||||
|
||||
MSGPACK_DEFINE_ARRAY(location, rotation);
|
||||
};
|
||||
using Transform = geom::Transform;
|
||||
|
||||
} // namespace rpc
|
||||
} // namespace carla
|
||||
|
|
|
@ -6,7 +6,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "carla/rpc/MsgPack.h"
|
||||
#include "carla/MsgPack.h"
|
||||
|
||||
namespace carla {
|
||||
namespace rpc {
|
||||
|
@ -55,6 +55,19 @@ namespace rpc {
|
|||
|
||||
#endif // LIBCARLA_INCLUDED_FROM_UE4
|
||||
|
||||
bool operator!=(const VehicleControl &rhs) const {
|
||||
return
|
||||
throttle != rhs.throttle ||
|
||||
steer != rhs.steer ||
|
||||
brake != rhs.brake ||
|
||||
hand_brake != rhs.hand_brake ||
|
||||
reverse != rhs.reverse;
|
||||
}
|
||||
|
||||
bool operator==(const VehicleControl &rhs) const {
|
||||
return !(*this != rhs);
|
||||
}
|
||||
|
||||
MSGPACK_DEFINE_ARRAY(
|
||||
throttle,
|
||||
steer,
|
||||
|
|
|
@ -0,0 +1,104 @@
|
|||
// 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 <type_traits>
|
||||
#include <utility>
|
||||
|
||||
namespace carla {
|
||||
namespace sensor {
|
||||
|
||||
namespace detail {
|
||||
|
||||
/// Private implementation of the CompileTimeTypeMap.
|
||||
template <size_t Size, typename...>
|
||||
struct CompileTimeTypeMapImpl;
|
||||
|
||||
/// Specialization for an empty map, it is retrieved when a key cannot be
|
||||
/// found.
|
||||
template <size_t Size>
|
||||
struct CompileTimeTypeMapImpl<Size> {
|
||||
|
||||
template <typename InKey>
|
||||
struct get {
|
||||
using type = void;
|
||||
static constexpr size_t index = Size;
|
||||
};
|
||||
|
||||
template <size_t Index>
|
||||
struct get_by_index {
|
||||
using type = void;
|
||||
using key = void;
|
||||
};
|
||||
};
|
||||
|
||||
template <size_t Size, typename Key, typename Value, typename... Rest>
|
||||
struct CompileTimeTypeMapImpl<Size, std::pair<Key, Value>, Rest...> {
|
||||
|
||||
static constexpr size_t current_index() {
|
||||
return Size - 1u - sizeof...(Rest);
|
||||
}
|
||||
|
||||
// Recursively call this struct until the InKey matches an element.
|
||||
template <typename InKey>
|
||||
struct get {
|
||||
using type = typename std::conditional<
|
||||
std::is_same<InKey, Key>::value,
|
||||
Value,
|
||||
typename CompileTimeTypeMapImpl<Size, Rest...>::template get<InKey>::type
|
||||
>::type;
|
||||
static constexpr size_t index =
|
||||
std::is_same<InKey, Key>::value ?
|
||||
current_index() :
|
||||
CompileTimeTypeMapImpl<Size, Rest...>::template get<InKey>::index;
|
||||
};
|
||||
|
||||
// Recursively call this struct until the Index matches an element.
|
||||
template <size_t Index>
|
||||
struct get_by_index {
|
||||
using type = typename std::conditional<
|
||||
Index == current_index(),
|
||||
Value,
|
||||
typename CompileTimeTypeMapImpl<Size, Rest...>::template get_by_index<Index>::type
|
||||
>::type;
|
||||
|
||||
using key = typename std::conditional<
|
||||
Index == current_index(),
|
||||
Key,
|
||||
typename CompileTimeTypeMapImpl<Size, Rest...>::template get_by_index<Index>::key
|
||||
>::type;
|
||||
};
|
||||
};
|
||||
|
||||
} // namespace detail
|
||||
|
||||
/// A compile time structure for mapping two types. Lookup elements by Key or
|
||||
/// by Index.
|
||||
///
|
||||
/// Example usage:
|
||||
///
|
||||
/// using MyMap = CompileTimeTypeMap<std::pair<A, B>, std::pair<C, D>>;
|
||||
/// using type_B = MyMap::get<A>::type;
|
||||
/// constexpr size_t index_B = MyMap::get<A>::index;
|
||||
/// using type_B_too = MyMap::get_by_index<index_B>::type;
|
||||
///
|
||||
template <typename... Items>
|
||||
struct CompileTimeTypeMap {
|
||||
|
||||
static constexpr size_t size() {
|
||||
return sizeof...(Items);
|
||||
}
|
||||
|
||||
template <typename InKey>
|
||||
using get = typename detail::CompileTimeTypeMapImpl<size(), Items...>::template get<InKey>;
|
||||
|
||||
template <size_t Index>
|
||||
using get_by_index = typename detail::CompileTimeTypeMapImpl<size(), Items...>::template get_by_index<Index>;
|
||||
};
|
||||
|
||||
} // namespace sensor
|
||||
} // namespace carla
|
|
@ -0,0 +1,95 @@
|
|||
// 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/Buffer.h"
|
||||
#include "carla/Memory.h"
|
||||
#include "carla/sensor/CompileTimeTypeMap.h"
|
||||
#include "carla/sensor/RawData.h"
|
||||
|
||||
namespace carla {
|
||||
namespace sensor {
|
||||
|
||||
class SensorData;
|
||||
|
||||
// ===========================================================================
|
||||
// -- CompositeSerializer ----------------------------------------------------
|
||||
// ===========================================================================
|
||||
|
||||
/// Compile-time map for mapping sensor objects to serializers. The
|
||||
/// appropriate serializer is called for each sensor to serialize and
|
||||
/// deserialize its data.
|
||||
///
|
||||
/// Do not use directly, use the SensorRegistry instantiation.
|
||||
template <typename... Items>
|
||||
class CompositeSerializer : public CompileTimeTypeMap<Items...> {
|
||||
using Super = CompileTimeTypeMap<Items...>;
|
||||
|
||||
public:
|
||||
|
||||
using interpreted_type = SharedPtr<SensorData>;
|
||||
|
||||
/// Serialize the arguments provided into a Buffer by calling to the
|
||||
/// serializer registered for the given @a Sensor type.
|
||||
template <typename Sensor, typename... Args>
|
||||
static Buffer Serialize(Sensor &sensor, Args &&... args);
|
||||
|
||||
/// Deserializes a Buffer by calling the "Deserialize" function of the
|
||||
/// serializer that generated the Buffer.
|
||||
static interpreted_type Deserialize(Buffer data);
|
||||
|
||||
private:
|
||||
|
||||
template <size_t Index, typename Data>
|
||||
static interpreted_type Deserialize_impl(Data &&data) {
|
||||
using Serializer = typename Super::template get_by_index<Index>::type;
|
||||
return Serializer::Deserialize(std::forward<Data>(data));
|
||||
}
|
||||
|
||||
template <typename Data, size_t... Is>
|
||||
static interpreted_type Deserialize_impl(size_t i, Data &&data, std::index_sequence<Is...>) {
|
||||
// This function is equivalent to creating a switch statement with a case
|
||||
// for each element in the map, the compiler should be able to optimize it
|
||||
// into a jump table. See https://stackoverflow.com/a/46282159/5308925.
|
||||
interpreted_type result;
|
||||
std::initializer_list<int> ({
|
||||
(i == Is ? (result = Deserialize_impl<Is>(std::forward<Data>(data))), 0 : 0)...
|
||||
});
|
||||
return result;
|
||||
}
|
||||
|
||||
template <typename Data>
|
||||
static interpreted_type Deserialize(size_t index, Data &&data) {
|
||||
return Deserialize_impl(
|
||||
index,
|
||||
std::forward<Data>(data),
|
||||
std::make_index_sequence<Super::size()>());
|
||||
}
|
||||
};
|
||||
|
||||
// ===========================================================================
|
||||
// -- CompositeSerializer implementation -------------------------------------
|
||||
// ===========================================================================
|
||||
|
||||
template <typename... Items>
|
||||
template <typename Sensor, typename... Args>
|
||||
inline Buffer CompositeSerializer<Items...>::Serialize(Sensor &sensor, Args &&... args) {
|
||||
using TheSensor = typename std::remove_const<Sensor>::type;
|
||||
using Serializer = typename Super::template get<TheSensor*>::type;
|
||||
return Serializer::Serialize(sensor, std::forward<Args>(args)...);
|
||||
}
|
||||
|
||||
template <typename... Items>
|
||||
inline typename CompositeSerializer<Items...>::interpreted_type
|
||||
CompositeSerializer<Items...>::Deserialize(Buffer data) {
|
||||
RawData message{std::move(data)};
|
||||
size_t index = message.GetSensorTypeId();
|
||||
return Deserialize(index, std::move(message));
|
||||
}
|
||||
|
||||
} // namespace sensor
|
||||
} // namespace carla
|
|
@ -0,0 +1,19 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "carla/sensor/Deserializer.h"
|
||||
|
||||
#include "carla/sensor/SensorRegistry.h"
|
||||
|
||||
namespace carla {
|
||||
namespace sensor {
|
||||
|
||||
SharedPtr<SensorData> Deserializer::Deserialize(Buffer buffer) {
|
||||
return SensorRegistry::Deserialize(std::move(buffer));
|
||||
}
|
||||
|
||||
} // namespace sensor
|
||||
} // namespace carla
|
|
@ -0,0 +1,29 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "carla/Buffer.h"
|
||||
#include "carla/Memory.h"
|
||||
|
||||
namespace carla {
|
||||
namespace sensor {
|
||||
|
||||
class SensorData;
|
||||
|
||||
/// Deserializes a Buffer containing data generated by a sensor and creates
|
||||
/// the appropriate SensorData class that contains the sensor's measurement.
|
||||
///
|
||||
/// This class encapsulates the SensorRegistry to avoid including all the
|
||||
/// serializers and SensorData classes.
|
||||
class Deserializer {
|
||||
public:
|
||||
|
||||
static SharedPtr<SensorData> Deserialize(Buffer buffer);
|
||||
};
|
||||
|
||||
} // namespace sensor
|
||||
} // namespace carla
|
|
@ -0,0 +1,92 @@
|
|||
// 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/Buffer.h"
|
||||
#include "carla/sensor/s11n/SensorHeaderSerializer.h"
|
||||
|
||||
#include <cstdint>
|
||||
#include <iterator>
|
||||
|
||||
namespace carla {
|
||||
namespace sensor {
|
||||
|
||||
/// Wrapper around the raw data generated by a sensor plus some useful
|
||||
/// meta-information.
|
||||
class RawData {
|
||||
using HeaderSerializer = s11n::SensorHeaderSerializer;
|
||||
private:
|
||||
|
||||
const auto &GetHeader() const {
|
||||
return HeaderSerializer::Deserialize(_buffer);
|
||||
}
|
||||
|
||||
public:
|
||||
|
||||
/// Type-id of the sensor that generated the data.
|
||||
uint64_t GetSensorTypeId() const {
|
||||
return GetHeader().sensor_type;
|
||||
}
|
||||
|
||||
/// Frame count when the data was generated.
|
||||
uint64_t GetFrameNumber() const {
|
||||
return GetHeader().frame_number;
|
||||
}
|
||||
|
||||
/// Sensor's transform when the data was generated.
|
||||
const rpc::Transform &GetSensorTransform() const {
|
||||
return GetHeader().sensor_transform;
|
||||
}
|
||||
|
||||
/// Begin iterator to the data generated by the sensor.
|
||||
auto begin() noexcept {
|
||||
return _buffer.begin() + HeaderSerializer::header_offset;
|
||||
}
|
||||
|
||||
/// @copydoc begin()
|
||||
auto begin() const noexcept {
|
||||
return _buffer.begin() + HeaderSerializer::header_offset;
|
||||
}
|
||||
|
||||
/// Past-the-end iterator to the data generated by the sensor.
|
||||
auto end() noexcept {
|
||||
return _buffer.end();
|
||||
}
|
||||
|
||||
/// @copydoc end()
|
||||
auto end() const noexcept {
|
||||
return _buffer.end();
|
||||
}
|
||||
|
||||
/// Retrieve a pointer to the memory containing the data generated by the
|
||||
/// sensor.
|
||||
auto data() noexcept {
|
||||
return begin();
|
||||
}
|
||||
|
||||
/// @copydoc data()
|
||||
auto data() const noexcept {
|
||||
return begin();
|
||||
}
|
||||
|
||||
/// Size in bytes of the data generated by the sensor.
|
||||
size_t size() const {
|
||||
return std::distance(begin(), end());
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
template <typename... Items>
|
||||
friend class CompositeSerializer;
|
||||
|
||||
RawData(Buffer buffer) : _buffer(std::move(buffer)) {}
|
||||
|
||||
Buffer _buffer;
|
||||
};
|
||||
|
||||
} // namespace sensor
|
||||
} // namespace carla
|
|
@ -0,0 +1,48 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "carla/Memory.h"
|
||||
#include "carla/NonCopyable.h"
|
||||
#include "carla/sensor/RawData.h"
|
||||
|
||||
namespace carla {
|
||||
namespace sensor {
|
||||
|
||||
/// Base class for all the objects containing data generated by a sensor.
|
||||
class SensorData
|
||||
: public EnableSharedFromThis<SensorData>,
|
||||
private NonCopyable {
|
||||
protected:
|
||||
|
||||
explicit SensorData(const RawData &data)
|
||||
: _frame_number(data.GetFrameNumber()),
|
||||
_sensor_transform(data.GetSensorTransform()) {}
|
||||
|
||||
public:
|
||||
|
||||
virtual ~SensorData() = default;
|
||||
|
||||
/// Frame count when the data was generated.
|
||||
size_t GetFrameNumber() const {
|
||||
return _frame_number;
|
||||
}
|
||||
|
||||
/// Sensor's transform when the data was generated.
|
||||
const rpc::Transform &GetSensorTransform() const {
|
||||
return _sensor_transform;
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
const size_t _frame_number;
|
||||
|
||||
const rpc::Transform _sensor_transform;
|
||||
};
|
||||
|
||||
} // namespace sensor
|
||||
} // namespace carla
|
|
@ -0,0 +1,53 @@
|
|||
// 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>.
|
||||
|
||||
#ifndef LIBCARLA_SENSOR_REGISTRY_INCLUDE_H
|
||||
#define LIBCARLA_SENSOR_REGISTRY_INCLUDE_H
|
||||
|
||||
#include "carla/sensor/CompositeSerializer.h"
|
||||
|
||||
// =============================================================================
|
||||
// Follow the 4 steps to register a new sensor.
|
||||
// =============================================================================
|
||||
|
||||
// 1. Include the serializer here.
|
||||
#include "carla/sensor/s11n/ImageSerializer.h"
|
||||
#include "carla/sensor/s11n/LidarSerializer.h"
|
||||
|
||||
// 2. Add a forward-declaration of the sensor here.
|
||||
class ADepthCamera;
|
||||
class ARayCastLidar;
|
||||
class ASceneCaptureCamera;
|
||||
class ASemanticSegmentationCamera;
|
||||
|
||||
namespace carla {
|
||||
namespace sensor {
|
||||
|
||||
// 3. Register the sensor and its serializer in the SensorRegistry.
|
||||
|
||||
/// Contains a registry of all the sensors available and allows serializing
|
||||
/// and deserializing sensor data for the types registered.
|
||||
using SensorRegistry = CompositeSerializer<
|
||||
std::pair<ASceneCaptureCamera *, s11n::ImageSerializer>,
|
||||
std::pair<ADepthCamera *, s11n::ImageSerializer>,
|
||||
std::pair<ASemanticSegmentationCamera *, s11n::ImageSerializer>,
|
||||
std::pair<ARayCastLidar *, s11n::LidarSerializer>
|
||||
>;
|
||||
|
||||
} // namespace sensor
|
||||
} // namespace carla
|
||||
|
||||
#endif // LIBCARLA_SENSOR_REGISTRY_INCLUDE_H
|
||||
|
||||
#ifdef LIBCARLA_SENSOR_REGISTRY_WITH_SENSOR_INCLUDES
|
||||
|
||||
// 4. Include the sensor here.
|
||||
#include "Carla/Sensor/DepthCamera.h"
|
||||
#include "Carla/Sensor/RayCastLidar.h"
|
||||
#include "Carla/Sensor/SceneCaptureCamera.h"
|
||||
#include "Carla/Sensor/SemanticSegmentationCamera.h"
|
||||
|
||||
#endif // LIBCARLA_SENSOR_REGISTRY_WITH_SENSOR_INCLUDES
|
|
@ -0,0 +1,109 @@
|
|||
// 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/Debug.h"
|
||||
#include "carla/sensor/SensorData.h"
|
||||
|
||||
#include <type_traits>
|
||||
#include <iterator>
|
||||
|
||||
namespace carla {
|
||||
namespace sensor {
|
||||
namespace data {
|
||||
|
||||
/// Base class for all the sensor data consisting of an array of items.
|
||||
template <typename T>
|
||||
class Array : public SensorData {
|
||||
public:
|
||||
|
||||
using value_type = T;
|
||||
using iterator = value_type *;
|
||||
using const_iterator = typename std::add_const<value_type>::type *;
|
||||
using size_type = typename std::iterator_traits<iterator>::difference_type;
|
||||
using pointer = typename std::iterator_traits<iterator>::pointer;
|
||||
using reference = typename std::iterator_traits<iterator>::reference;
|
||||
|
||||
iterator begin() {
|
||||
return reinterpret_cast<iterator>(_data.begin() + _offset);
|
||||
}
|
||||
|
||||
const_iterator cbegin() const {
|
||||
return reinterpret_cast<const_iterator>(_data.begin() + _offset);
|
||||
}
|
||||
|
||||
const_iterator begin() const {
|
||||
return cbegin();
|
||||
}
|
||||
|
||||
iterator end() {
|
||||
return reinterpret_cast<iterator>(_data.end());
|
||||
}
|
||||
|
||||
const_iterator cend() const {
|
||||
return reinterpret_cast<const_iterator>(_data.end());
|
||||
}
|
||||
|
||||
const_iterator end() const {
|
||||
return cend();
|
||||
}
|
||||
|
||||
bool empty() const {
|
||||
return begin() == end();
|
||||
}
|
||||
|
||||
size_type size() const {
|
||||
return std::distance(begin(), end());
|
||||
}
|
||||
|
||||
value_type *data() {
|
||||
return begin();
|
||||
}
|
||||
|
||||
const value_type *data() const {
|
||||
return begin();
|
||||
}
|
||||
|
||||
reference operator[](size_type i) {
|
||||
return data()[i];
|
||||
}
|
||||
|
||||
const reference operator[](size_type i) const {
|
||||
return data()[i];
|
||||
}
|
||||
|
||||
protected:
|
||||
|
||||
explicit Array(size_t offset, RawData data)
|
||||
: SensorData(data),
|
||||
_data(std::move(data)) {
|
||||
SetOffset(offset);
|
||||
}
|
||||
|
||||
explicit Array(RawData data)
|
||||
: Array(0u, std::move(data)) {}
|
||||
|
||||
void SetOffset(size_t offset) {
|
||||
DEBUG_ASSERT(_data.size() >= _offset);
|
||||
DEBUG_ASSERT((_data.size() - _offset) % sizeof(T) == 0u);
|
||||
_offset = offset;
|
||||
}
|
||||
|
||||
const RawData &GetRawData() const {
|
||||
return _data;
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
size_t _offset;
|
||||
|
||||
RawData _data;
|
||||
};
|
||||
|
||||
} // namespace data
|
||||
} // namespace sensor
|
||||
} // namespace carla
|
|
@ -9,11 +9,19 @@
|
|||
#include <cstdint>
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
namespace sensor {
|
||||
namespace data {
|
||||
|
||||
#pragma pack(push, 1)
|
||||
/// A 32-bit BGRA color.
|
||||
struct Color {
|
||||
Color() = default;
|
||||
Color(uint8_t r, uint8_t g, uint8_t b) : r(r), g(g), b(b) {}
|
||||
Color(const Color &) = default;
|
||||
|
||||
Color(uint8_t r, uint8_t g, uint8_t b, uint8_t a = 255u)
|
||||
: b(b), g(g), r(r), a(a) {}
|
||||
|
||||
Color &operator=(const Color &) = default;
|
||||
|
||||
bool operator==(const Color &rhs) const {
|
||||
return (r == rhs.r) && (g == rhs.g) && (b == rhs.b);
|
||||
|
@ -23,10 +31,15 @@ namespace client {
|
|||
return !(*this == rhs);
|
||||
}
|
||||
|
||||
uint8_t r = 0u;
|
||||
uint8_t g = 0u;
|
||||
uint8_t b = 0u;
|
||||
uint8_t g = 0u;
|
||||
uint8_t r = 0u;
|
||||
uint8_t a = 0u;
|
||||
};
|
||||
#pragma pack(pop)
|
||||
|
||||
} // namespace client
|
||||
static_assert(sizeof(Color) == sizeof(uint32_t), "Invalid color size!");
|
||||
|
||||
} // namespace data
|
||||
} // namespace sensor
|
||||
} // namespace carla
|
|
@ -0,0 +1,21 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "carla/sensor/data/Color.h"
|
||||
#include "carla/sensor/data/ImageTmpl.h"
|
||||
|
||||
namespace carla {
|
||||
namespace sensor {
|
||||
namespace data {
|
||||
|
||||
/// An image of 32-bit BGRA colors.
|
||||
using Image = ImageTmpl<Color>;
|
||||
|
||||
} // namespace data
|
||||
} // namespace sensor
|
||||
} // namespace carla
|
|
@ -0,0 +1,60 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "carla/Debug.h"
|
||||
#include "carla/sensor/data/Array.h"
|
||||
#include "carla/sensor/s11n/ImageSerializer.h"
|
||||
|
||||
namespace carla {
|
||||
namespace sensor {
|
||||
namespace data {
|
||||
|
||||
/// Templated image for any type of pixel.
|
||||
template <typename PixelT>
|
||||
class ImageTmpl : public Array<PixelT> {
|
||||
using Super = Array<PixelT>;
|
||||
protected:
|
||||
|
||||
using Serializer = s11n::ImageSerializer;
|
||||
|
||||
friend Serializer;
|
||||
|
||||
explicit ImageTmpl(RawData data)
|
||||
: Super(Serializer::header_offset, std::move(data)) {
|
||||
DEBUG_ASSERT(GetWidth() * GetHeight() == Super::size());
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
const auto &GetHeader() const {
|
||||
return Serializer::DeserializeHeader(Super::GetRawData());
|
||||
}
|
||||
|
||||
public:
|
||||
|
||||
using pixel_type = PixelT;
|
||||
|
||||
/// Get image width in pixels.
|
||||
auto GetWidth() const {
|
||||
return GetHeader().width;
|
||||
}
|
||||
|
||||
/// Get image height in pixels.
|
||||
auto GetHeight() const {
|
||||
return GetHeader().height;
|
||||
}
|
||||
|
||||
/// Get horizontal field of view of the image in degrees.
|
||||
auto GetFOVAngle() const {
|
||||
return GetHeader().fov_angle;
|
||||
}
|
||||
};
|
||||
|
||||
} // namespace data
|
||||
} // namespace sensor
|
||||
} // namespace carla
|
|
@ -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
|
||||
|
||||
#include "carla/Debug.h"
|
||||
#include "carla/rpc/Location.h"
|
||||
#include "carla/sensor/data/Array.h"
|
||||
#include "carla/sensor/s11n/LidarSerializer.h"
|
||||
|
||||
namespace carla {
|
||||
namespace sensor {
|
||||
namespace data {
|
||||
|
||||
/// Measurement produced by a Lidar. Consists of an array of 3D points plus
|
||||
/// some extra meta-information about the Lidar.
|
||||
class LidarMeasurement : public Array<rpc::Location> {
|
||||
static_assert(sizeof(rpc::Location) == 3u * sizeof(float), "Location size missmatch");
|
||||
using Super = Array<rpc::Location>;
|
||||
protected:
|
||||
|
||||
using Serializer = s11n::LidarSerializer;
|
||||
|
||||
friend Serializer;
|
||||
|
||||
explicit LidarMeasurement(RawData data)
|
||||
: Super(std::move(data)) {
|
||||
Super::SetOffset(Serializer::GetHeaderOffset(Super::GetRawData()));
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
auto GetHeader() const {
|
||||
return Serializer::DeserializeHeader(Super::GetRawData());
|
||||
}
|
||||
|
||||
public:
|
||||
|
||||
/// Horizontal angle of the Lidar at the time of the measurement.
|
||||
auto GetHorizontalAngle() const {
|
||||
return GetHeader().GetHorizontalAngle();
|
||||
}
|
||||
|
||||
/// Number of channels of the Lidar.
|
||||
auto GetChannelCount() const {
|
||||
return GetHeader().GetChannelCount();
|
||||
}
|
||||
|
||||
/// Retrieve the number of points that @a channel generated. Points are
|
||||
/// sorted by channel, so this method allows to identify the channel that
|
||||
/// generated each point.
|
||||
auto GetPointCount(size_t channel) const {
|
||||
return GetHeader().GetPointCount(channel);
|
||||
}
|
||||
};
|
||||
|
||||
} // namespace data
|
||||
} // namespace sensor
|
||||
} // namespace carla
|
|
@ -0,0 +1,21 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "carla/sensor/s11n/ImageSerializer.h"
|
||||
|
||||
#include "carla/sensor/data/Image.h"
|
||||
|
||||
namespace carla {
|
||||
namespace sensor {
|
||||
namespace s11n {
|
||||
|
||||
SharedPtr<SensorData> ImageSerializer::Deserialize(RawData data) {
|
||||
return SharedPtr<data::Image>(new data::Image{std::move(data)});
|
||||
}
|
||||
|
||||
} // namespace s11n
|
||||
} // namespace sensor
|
||||
} // namespace carla
|
|
@ -0,0 +1,60 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "carla/Memory.h"
|
||||
#include "carla/sensor/RawData.h"
|
||||
|
||||
#include <cstdint>
|
||||
#include <cstring>
|
||||
|
||||
namespace carla {
|
||||
namespace sensor {
|
||||
|
||||
class SensorData;
|
||||
|
||||
namespace s11n {
|
||||
|
||||
/// Serializes image buffers generated by camera sensors.
|
||||
class ImageSerializer {
|
||||
public:
|
||||
|
||||
#pragma pack(push, 1)
|
||||
struct ImageHeader {
|
||||
uint32_t width;
|
||||
uint32_t height;
|
||||
float fov_angle;
|
||||
};
|
||||
#pragma pack(pop)
|
||||
|
||||
constexpr static auto header_offset = sizeof(ImageHeader);
|
||||
|
||||
static const ImageHeader &DeserializeHeader(const RawData &data) {
|
||||
return *reinterpret_cast<const ImageHeader *>(data.begin());
|
||||
}
|
||||
|
||||
template <typename Sensor>
|
||||
static Buffer Serialize(const Sensor &sensor, Buffer bitmap);
|
||||
|
||||
static SharedPtr<SensorData> Deserialize(RawData data);
|
||||
};
|
||||
|
||||
template <typename Sensor>
|
||||
inline Buffer ImageSerializer::Serialize(const Sensor &sensor, Buffer bitmap) {
|
||||
DEBUG_ASSERT(bitmap.size() > sizeof(ImageHeader));
|
||||
ImageHeader header = {
|
||||
sensor.GetImageWidth(),
|
||||
sensor.GetImageHeight(),
|
||||
sensor.GetFOVAngle()
|
||||
};
|
||||
std::memcpy(bitmap.data(), reinterpret_cast<const void *>(&header), sizeof(header));
|
||||
return bitmap;
|
||||
}
|
||||
|
||||
} // namespace s11n
|
||||
} // namespace sensor
|
||||
} // namespace carla
|
|
@ -0,0 +1,98 @@
|
|||
// 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/rpc/Location.h"
|
||||
|
||||
#include <cstdint>
|
||||
#include <vector>
|
||||
|
||||
namespace carla {
|
||||
namespace sensor {
|
||||
namespace s11n {
|
||||
|
||||
/// Helper class to store and serialize the data generated by a Lidar.
|
||||
///
|
||||
/// The header of a Lidar measurement consists of an array of uint32_t's in
|
||||
/// the following layout
|
||||
///
|
||||
/// {
|
||||
/// Horizontal angle (float),
|
||||
/// Channel count,
|
||||
/// Point count of channel 0,
|
||||
/// ...
|
||||
/// Point count of channel n,
|
||||
/// }
|
||||
///
|
||||
/// The points are stored in an array of floats
|
||||
///
|
||||
/// {
|
||||
/// X0, Y0, Z0,
|
||||
/// ...
|
||||
/// Xn, Yn, Zn,
|
||||
/// }
|
||||
///
|
||||
/// @warning WritePoint should be called sequentially in the order in which
|
||||
/// the points are going to be stored, i.e., starting at channel zero and
|
||||
/// increasing steadily.
|
||||
class LidarMeasurement {
|
||||
static_assert(sizeof(float) == sizeof(uint32_t), "Invalid float size");
|
||||
|
||||
friend class LidarSerializer;
|
||||
friend class LidarHeaderView;
|
||||
|
||||
enum Index : size_t {
|
||||
HorizontalAngle,
|
||||
ChannelCount,
|
||||
SIZE
|
||||
};
|
||||
|
||||
public:
|
||||
|
||||
explicit LidarMeasurement(uint32_t ChannelCount = 0u)
|
||||
: _header(Index::SIZE + ChannelCount, 0u) {
|
||||
_header[Index::ChannelCount] = ChannelCount;
|
||||
}
|
||||
|
||||
LidarMeasurement &operator=(LidarMeasurement &&) = default;
|
||||
|
||||
float GetHorizontalAngle() const {
|
||||
return reinterpret_cast<const float &>(_header[Index::HorizontalAngle]);
|
||||
}
|
||||
|
||||
void SetHorizontalAngle(float angle) {
|
||||
_header[Index::HorizontalAngle] = reinterpret_cast<const uint32_t &>(angle);
|
||||
}
|
||||
|
||||
uint32_t GetChannelCount() const {
|
||||
return _header[Index::ChannelCount];
|
||||
}
|
||||
|
||||
void Reset(uint32_t total_point_count) {
|
||||
std::memset(_header.data() + Index::SIZE, 0, sizeof(uint32_t) * GetChannelCount());
|
||||
_points.clear();
|
||||
_points.reserve(3u * total_point_count);
|
||||
}
|
||||
|
||||
void WritePoint(uint32_t channel, rpc::Location point) {
|
||||
DEBUG_ASSERT(GetChannelCount() > channel);
|
||||
_header[Index::SIZE + channel] += 1u;
|
||||
_points.emplace_back(point.x);
|
||||
_points.emplace_back(point.y);
|
||||
_points.emplace_back(point.z);
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
std::vector<uint32_t> _header;
|
||||
|
||||
std::vector<float> _points;
|
||||
};
|
||||
|
||||
} // namespace s11n
|
||||
} // namespace sensor
|
||||
} // namespace carla
|
|
@ -0,0 +1,22 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "carla/sensor/s11n/LidarSerializer.h"
|
||||
|
||||
#include "carla/sensor/data/LidarMeasurement.h"
|
||||
|
||||
namespace carla {
|
||||
namespace sensor {
|
||||
namespace s11n {
|
||||
|
||||
SharedPtr<SensorData> LidarSerializer::Deserialize(RawData data) {
|
||||
return SharedPtr<data::LidarMeasurement>(
|
||||
new data::LidarMeasurement{std::move(data)});
|
||||
}
|
||||
|
||||
} // namespace s11n
|
||||
} // namespace sensor
|
||||
} // namespace carla
|
|
@ -0,0 +1,98 @@
|
|||
// 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/Debug.h"
|
||||
#include "carla/Memory.h"
|
||||
#include "carla/sensor/RawData.h"
|
||||
#include "carla/sensor/s11n/LidarMeasurement.h"
|
||||
|
||||
namespace carla {
|
||||
namespace sensor {
|
||||
|
||||
class SensorData;
|
||||
|
||||
namespace s11n {
|
||||
|
||||
// ===========================================================================
|
||||
// -- LidarHeaderView --------------------------------------------------------
|
||||
// ===========================================================================
|
||||
|
||||
/// A view over the header of a Lidar measurement.
|
||||
class LidarHeaderView {
|
||||
using Index = LidarMeasurement::Index;
|
||||
public:
|
||||
|
||||
float GetHorizontalAngle() const {
|
||||
return reinterpret_cast<const float &>(_begin[Index::HorizontalAngle]);
|
||||
}
|
||||
|
||||
uint32_t GetChannelCount() const {
|
||||
return _begin[Index::ChannelCount];
|
||||
}
|
||||
|
||||
uint32_t GetPointCount(size_t channel) const {
|
||||
DEBUG_ASSERT(channel < GetChannelCount());
|
||||
return _begin[Index::SIZE + channel];
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
friend class LidarSerializer;
|
||||
|
||||
explicit LidarHeaderView(const uint32_t *begin) : _begin(begin) {
|
||||
DEBUG_ASSERT(_begin != nullptr);
|
||||
}
|
||||
|
||||
const uint32_t *_begin;
|
||||
};
|
||||
|
||||
// ===========================================================================
|
||||
// -- LidarSerializer --------------------------------------------------------
|
||||
// ===========================================================================
|
||||
|
||||
/// Serializes the data generated by Lidar sensors.
|
||||
class LidarSerializer {
|
||||
public:
|
||||
|
||||
static LidarHeaderView DeserializeHeader(const RawData &data) {
|
||||
return LidarHeaderView{reinterpret_cast<const uint32_t *>(data.begin())};
|
||||
}
|
||||
|
||||
static size_t GetHeaderOffset(const RawData &data) {
|
||||
auto View = DeserializeHeader(data);
|
||||
return sizeof(uint32_t) * (View.GetChannelCount() + LidarMeasurement::Index::SIZE);
|
||||
}
|
||||
|
||||
template <typename Sensor>
|
||||
static Buffer Serialize(
|
||||
const Sensor &sensor,
|
||||
const LidarMeasurement &measurement,
|
||||
Buffer bitmap);
|
||||
|
||||
static SharedPtr<SensorData> Deserialize(RawData data);
|
||||
};
|
||||
|
||||
// ===========================================================================
|
||||
// -- LidarSerializer implementation -----------------------------------------
|
||||
// ===========================================================================
|
||||
|
||||
template <typename Sensor>
|
||||
inline Buffer LidarSerializer::Serialize(
|
||||
const Sensor &,
|
||||
const LidarMeasurement &measurement,
|
||||
Buffer output) {
|
||||
std::array<boost::asio::const_buffer, 2u> seq = {
|
||||
boost::asio::buffer(measurement._header),
|
||||
boost::asio::buffer(measurement._points)};
|
||||
output.copy_from(seq);
|
||||
return output;
|
||||
}
|
||||
|
||||
} // namespace s11n
|
||||
} // namespace sensor
|
||||
} // namespace carla
|
|
@ -0,0 +1,39 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "carla/sensor/s11n/SensorHeaderSerializer.h"
|
||||
|
||||
#include "carla/BufferPool.h"
|
||||
|
||||
namespace carla {
|
||||
namespace sensor {
|
||||
namespace s11n {
|
||||
|
||||
static_assert(
|
||||
SensorHeaderSerializer::header_offset == 2u * 8u + 6u * 4u,
|
||||
"Header size missmatch");
|
||||
|
||||
static Buffer PopBufferFromPool() {
|
||||
static auto pool = std::make_shared<BufferPool>();
|
||||
return pool->Pop();
|
||||
}
|
||||
|
||||
Buffer SensorHeaderSerializer::Serialize(
|
||||
const uint64_t index,
|
||||
const uint64_t frame,
|
||||
const rpc::Transform transform) {
|
||||
Header h;
|
||||
h.sensor_type = index;
|
||||
h.frame_number = frame;
|
||||
h.sensor_transform = transform;
|
||||
auto buffer = PopBufferFromPool();
|
||||
buffer.copy_from(reinterpret_cast<const unsigned char *>(&h), sizeof(h));
|
||||
return buffer;
|
||||
}
|
||||
|
||||
} // namespace s11n
|
||||
} // namespace sensor
|
||||
} // namespace carla
|
|
@ -0,0 +1,39 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "carla/Buffer.h"
|
||||
#include "carla/rpc/Transform.h"
|
||||
|
||||
namespace carla {
|
||||
namespace sensor {
|
||||
namespace s11n {
|
||||
|
||||
/// Serializes the meta-information (header) sent with all the sensor data.
|
||||
class SensorHeaderSerializer {
|
||||
public:
|
||||
|
||||
#pragma pack(push, 1)
|
||||
struct Header {
|
||||
uint64_t sensor_type;
|
||||
uint64_t frame_number;
|
||||
rpc::Transform sensor_transform;
|
||||
};
|
||||
#pragma pack(pop)
|
||||
|
||||
constexpr static auto header_offset = sizeof(Header);
|
||||
|
||||
static Buffer Serialize(uint64_t index, uint64_t frame, rpc::Transform transform);
|
||||
|
||||
static const Header &Deserialize(const Buffer &message) {
|
||||
return *reinterpret_cast<const Header *>(message.data());
|
||||
}
|
||||
};
|
||||
|
||||
} // namespace s11n
|
||||
} // namespace sensor
|
||||
} // namespace carla
|
|
@ -7,8 +7,8 @@
|
|||
#pragma once
|
||||
|
||||
#include "carla/Logging.h"
|
||||
#include "carla/ThreadGroup.h"
|
||||
#include "carla/streaming/Token.h"
|
||||
#include "carla/streaming/detail/AsioThreadPool.h"
|
||||
#include "carla/streaming/detail/tcp/Client.h"
|
||||
#include "carla/streaming/low_level/Client.h"
|
||||
|
||||
|
@ -21,48 +21,40 @@ namespace streaming {
|
|||
|
||||
/// A client able to subscribe to multiple streams.
|
||||
class Client {
|
||||
using underlying_client = low_level::Client<detail::tcp::Client>;
|
||||
public:
|
||||
|
||||
explicit Client()
|
||||
: _io_service(),
|
||||
_work_to_do(_io_service) {}
|
||||
Client() = default;
|
||||
|
||||
explicit Client(const std::string &fallback_address)
|
||||
: _io_service(),
|
||||
_work_to_do(_io_service),
|
||||
_client(fallback_address) {}
|
||||
: _client(fallback_address) {}
|
||||
|
||||
~Client() {
|
||||
Stop();
|
||||
_service.Stop();
|
||||
}
|
||||
|
||||
template <typename Functor>
|
||||
void Subscribe(const Token &token, Functor &&callback) {
|
||||
_client.Subscribe(_io_service, token, std::forward<Functor>(callback));
|
||||
_client.Subscribe(_service.service(), token, std::forward<Functor>(callback));
|
||||
}
|
||||
|
||||
void UnSubscribe(const Token &token) {
|
||||
_client.UnSubscribe(token);
|
||||
}
|
||||
|
||||
void Run() {
|
||||
_io_service.run();
|
||||
_service.Run();
|
||||
}
|
||||
|
||||
void AsyncRun(size_t worker_threads) {
|
||||
_workers.CreateThreads(worker_threads, [this]() { Run(); });
|
||||
}
|
||||
|
||||
void Stop() {
|
||||
_io_service.stop();
|
||||
_workers.JoinAll();
|
||||
_service.AsyncRun(worker_threads);
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
using underlying_client = low_level::Client<detail::tcp::Client>;
|
||||
// The order of these two arguments is very important.
|
||||
|
||||
boost::asio::io_service _io_service;
|
||||
|
||||
boost::asio::io_service::work _work_to_do;
|
||||
|
||||
ThreadGroup _workers;
|
||||
detail::AsioThreadPool _service;
|
||||
|
||||
underlying_client _client;
|
||||
};
|
||||
|
|
|
@ -6,9 +6,9 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "carla/ThreadGroup.h"
|
||||
#include "carla/streaming/low_level/Server.h"
|
||||
#include "carla/streaming/detail/AsioThreadPool.h"
|
||||
#include "carla/streaming/detail/tcp/Server.h"
|
||||
#include "carla/streaming/low_level/Server.h"
|
||||
|
||||
#include <boost/asio/io_service.hpp>
|
||||
|
||||
|
@ -23,21 +23,21 @@ namespace streaming {
|
|||
public:
|
||||
|
||||
explicit Server(uint16_t port)
|
||||
: _server(_io_service, make_endpoint<protocol_type>(port)) {}
|
||||
: _server(_service.service(), make_endpoint<protocol_type>(port)) {}
|
||||
|
||||
explicit Server(const std::string &address, uint16_t port)
|
||||
: _server(_io_service, make_endpoint<protocol_type>(address, port)) {}
|
||||
: _server(_service.service(), make_endpoint<protocol_type>(address, port)) {}
|
||||
|
||||
explicit Server(
|
||||
const std::string &address, uint16_t port,
|
||||
const std::string &external_address, uint16_t external_port)
|
||||
: _server(
|
||||
_io_service,
|
||||
_service.service(),
|
||||
make_endpoint<protocol_type>(address, port),
|
||||
make_endpoint<protocol_type>(external_address, external_port)) {}
|
||||
|
||||
~Server() {
|
||||
Stop();
|
||||
_service.Stop();
|
||||
}
|
||||
|
||||
void SetTimeout(time_duration timeout) {
|
||||
|
@ -49,25 +49,20 @@ namespace streaming {
|
|||
}
|
||||
|
||||
void Run() {
|
||||
_io_service.run();
|
||||
_service.Run();
|
||||
}
|
||||
|
||||
void AsyncRun(size_t worker_threads) {
|
||||
_workers.CreateThreads(worker_threads, [this](){ Run(); });
|
||||
}
|
||||
|
||||
void Stop() {
|
||||
_io_service.stop();
|
||||
_workers.JoinAll();
|
||||
_service.AsyncRun(worker_threads);
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
boost::asio::io_service _io_service;
|
||||
// The order of these two arguments is very important.
|
||||
|
||||
detail::AsioThreadPool _service;
|
||||
|
||||
underlying_server _server;
|
||||
|
||||
ThreadGroup _workers;
|
||||
};
|
||||
|
||||
} // namespace streaming
|
||||
|
|
|
@ -6,7 +6,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "carla/rpc/MsgPack.h"
|
||||
#include "carla/MsgPack.h"
|
||||
|
||||
#include <array>
|
||||
|
||||
|
|
|
@ -0,0 +1,60 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "carla/NonCopyable.h"
|
||||
#include "carla/ThreadGroup.h"
|
||||
#include "carla/profiler/LifetimeProfiled.h"
|
||||
|
||||
#include <boost/asio/io_service.hpp>
|
||||
|
||||
namespace carla {
|
||||
namespace streaming {
|
||||
namespace detail {
|
||||
|
||||
class AsioThreadPool
|
||||
: private profiler::LifetimeProfiled,
|
||||
private NonCopyable {
|
||||
public:
|
||||
|
||||
AsioThreadPool()
|
||||
: LIBCARLA_INITIALIZE_LIFETIME_PROFILER("AsioThreadPool"),
|
||||
_work_to_do(_io_service) {}
|
||||
|
||||
~AsioThreadPool() {
|
||||
Stop();
|
||||
}
|
||||
|
||||
auto &service() {
|
||||
return _io_service;
|
||||
}
|
||||
|
||||
void Run() {
|
||||
_io_service.run();
|
||||
}
|
||||
|
||||
void AsyncRun(size_t worker_threads) {
|
||||
_workers.CreateThreads(worker_threads, [this]() { Run(); });
|
||||
}
|
||||
|
||||
void Stop() {
|
||||
_io_service.stop();
|
||||
_workers.JoinAll();
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
boost::asio::io_service _io_service;
|
||||
|
||||
boost::asio::io_service::work _work_to_do;
|
||||
|
||||
ThreadGroup _workers;
|
||||
};
|
||||
|
||||
} // namespace detail
|
||||
} // namespace streaming
|
||||
} // namespace carla
|
|
@ -14,6 +14,15 @@ namespace carla {
|
|||
namespace streaming {
|
||||
namespace detail {
|
||||
|
||||
Dispatcher::~Dispatcher() {
|
||||
// Disconnect all the sessions from their streams, this should kill any
|
||||
// session remaining since at this point the io_service should be already
|
||||
// stopped.
|
||||
for (auto &pair : _stream_map) {
|
||||
pair.second->set_session(nullptr);
|
||||
}
|
||||
}
|
||||
|
||||
Stream Dispatcher::MakeStream() {
|
||||
std::lock_guard<std::mutex> lock(_mutex);
|
||||
++_cached_token._token.stream_id; // id zero only happens in overflow.
|
||||
|
|
|
@ -28,6 +28,8 @@ namespace detail {
|
|||
explicit Dispatcher(const EndPoint<Protocol, EndPointType> &ep)
|
||||
: _cached_token(0u, ep) {}
|
||||
|
||||
~Dispatcher();
|
||||
|
||||
Stream MakeStream();
|
||||
|
||||
void RegisterSession(std::shared_ptr<Session> session);
|
||||
|
@ -40,6 +42,8 @@ namespace detail {
|
|||
|
||||
token_type _cached_token;
|
||||
|
||||
/// @todo StreamStates should be cleaned up at some point, otherwise we keep
|
||||
/// them alive the whole run.
|
||||
std::unordered_map<
|
||||
stream_id_type,
|
||||
std::shared_ptr<StreamState>> _stream_map;
|
||||
|
|
|
@ -1,48 +0,0 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "carla/streaming/detail/Types.h"
|
||||
|
||||
#include <functional>
|
||||
|
||||
namespace carla {
|
||||
namespace streaming {
|
||||
namespace detail {
|
||||
|
||||
/// A wrapper to put clients into std::unordered_set.
|
||||
template <typename T>
|
||||
class HashableClient : public T {
|
||||
public:
|
||||
|
||||
template <typename ... Args>
|
||||
HashableClient(Args && ... args)
|
||||
: T(std::forward<Args>(args) ...) {}
|
||||
|
||||
bool operator==(const HashableClient &rhs) const {
|
||||
return T::GetStreamId() == rhs.GetStreamId();
|
||||
}
|
||||
};
|
||||
|
||||
} // namespace detail
|
||||
} // namespace streaming
|
||||
} // namespace carla
|
||||
|
||||
namespace std {
|
||||
|
||||
// Injecting a hash function for our clients into std namespace so we can
|
||||
// directly insert them into std::unordered_set.
|
||||
template <typename T>
|
||||
struct hash<carla::streaming::detail::HashableClient<T>> {
|
||||
using argument_type = carla::streaming::detail::HashableClient<T>;
|
||||
using result_type = std::size_t;
|
||||
result_type operator()(const argument_type &client) const noexcept {
|
||||
return std::hash<carla::streaming::detail::stream_id_type>()(client.GetStreamId());
|
||||
}
|
||||
};
|
||||
|
||||
} // namespace std
|
|
@ -66,7 +66,9 @@ namespace tcp {
|
|||
boost::asio::io_service &io_service,
|
||||
const token_type &token,
|
||||
callback_function_type callback)
|
||||
: _token(token),
|
||||
: LIBCARLA_INITIALIZE_LIFETIME_PROFILER(
|
||||
std::string("tcp client ") + std::to_string(token.get_stream_id())),
|
||||
_token(token),
|
||||
_callback(std::move(callback)),
|
||||
_socket(io_service),
|
||||
_strand(io_service),
|
||||
|
@ -75,25 +77,13 @@ namespace tcp {
|
|||
if (!_token.protocol_is_tcp()) {
|
||||
throw std::invalid_argument("invalid token, only TCP tokens supported");
|
||||
}
|
||||
Connect();
|
||||
}
|
||||
|
||||
Client::~Client() {
|
||||
Stop();
|
||||
}
|
||||
|
||||
void Client::Stop() {
|
||||
_connection_timer.cancel();
|
||||
_strand.post([this]() {
|
||||
_done = true;
|
||||
if (_socket.is_open()) {
|
||||
_socket.close();
|
||||
}
|
||||
});
|
||||
}
|
||||
Client::~Client() = default;
|
||||
|
||||
void Client::Connect() {
|
||||
_strand.post([this]() {
|
||||
auto self = shared_from_this();
|
||||
_strand.post([this, self]() {
|
||||
if (_done) {
|
||||
return;
|
||||
}
|
||||
|
@ -108,8 +98,11 @@ namespace tcp {
|
|||
DEBUG_ASSERT(_token.protocol_is_tcp());
|
||||
const auto ep = _token.to_tcp_endpoint();
|
||||
|
||||
auto handle_connect = [=](error_code ec) {
|
||||
auto handle_connect = [this, self, ep](error_code ec) {
|
||||
if (!ec) {
|
||||
if (_done) {
|
||||
return;
|
||||
}
|
||||
log_debug("streaming client: connected to", ep);
|
||||
// Send the stream id to subscribe to the stream.
|
||||
const auto &stream_id = _token.get_stream_id();
|
||||
|
@ -124,12 +117,12 @@ namespace tcp {
|
|||
ReadData();
|
||||
} else {
|
||||
// Else try again.
|
||||
log_warning("streaming client: failed to send stream id:", ec.message());
|
||||
log_info("streaming client: failed to send stream id:", ec.message());
|
||||
Connect();
|
||||
}
|
||||
}));
|
||||
} else {
|
||||
log_warning("streaming client: connection failed:", ec.message());
|
||||
log_info("streaming client: connection failed:", ec.message());
|
||||
Reconnect();
|
||||
}
|
||||
};
|
||||
|
@ -139,9 +132,21 @@ namespace tcp {
|
|||
});
|
||||
}
|
||||
|
||||
void Client::Stop() {
|
||||
_connection_timer.cancel();
|
||||
auto self = shared_from_this();
|
||||
_strand.post([this, self]() {
|
||||
_done = true;
|
||||
if (_socket.is_open()) {
|
||||
_socket.close();
|
||||
}
|
||||
});
|
||||
}
|
||||
|
||||
void Client::Reconnect() {
|
||||
auto self = shared_from_this();
|
||||
_connection_timer.expires_from_now(time_duration::seconds(1u));
|
||||
_connection_timer.async_wait([this](boost::system::error_code ec) {
|
||||
_connection_timer.async_wait([this, self](boost::system::error_code ec) {
|
||||
if (!ec) {
|
||||
Connect();
|
||||
}
|
||||
|
@ -149,7 +154,8 @@ namespace tcp {
|
|||
}
|
||||
|
||||
void Client::ReadData() {
|
||||
_strand.post([this]() {
|
||||
auto self = shared_from_this();
|
||||
_strand.post([this, self]() {
|
||||
if (_done) {
|
||||
return;
|
||||
}
|
||||
|
@ -158,7 +164,7 @@ namespace tcp {
|
|||
|
||||
auto message = std::make_shared<IncomingMessage>(_buffer_pool->Pop());
|
||||
|
||||
auto handle_read_data = [=](boost::system::error_code ec, size_t DEBUG_ONLY(bytes)) {
|
||||
auto handle_read_data = [this, self, message](boost::system::error_code ec, size_t DEBUG_ONLY(bytes)) {
|
||||
DEBUG_ONLY(log_debug("streaming client: Client::ReadData.handle_read_data", bytes, "bytes"));
|
||||
if (!ec) {
|
||||
DEBUG_ASSERT_EQ(bytes, message->size());
|
||||
|
@ -166,19 +172,24 @@ namespace tcp {
|
|||
// Move the buffer to the callback function and start reading the next
|
||||
// piece of data.
|
||||
log_debug("streaming client: success reading data, calling the callback");
|
||||
_socket.get_io_service().post([this, message]() { _callback(message->pop()); });
|
||||
_socket.get_io_service().post([self, message]() { self->_callback(message->pop()); });
|
||||
ReadData();
|
||||
} else {
|
||||
// As usual, if anything fails start over from the very top.
|
||||
log_warning("streaming client: failed to read data:", ec.message());
|
||||
log_info("streaming client: failed to read data:", ec.message());
|
||||
Connect();
|
||||
}
|
||||
};
|
||||
|
||||
auto handle_read_header = [=](boost::system::error_code ec, size_t DEBUG_ONLY(bytes)) {
|
||||
auto handle_read_header = [this, self, message, handle_read_data](
|
||||
boost::system::error_code ec,
|
||||
size_t DEBUG_ONLY(bytes)) {
|
||||
DEBUG_ONLY(log_debug("streaming client: Client::ReadData.handle_read_header", bytes, "bytes"));
|
||||
if (!ec && (message->size() > 0u)) {
|
||||
DEBUG_ASSERT_EQ(bytes, sizeof(message_size_type));
|
||||
if (_done) {
|
||||
return;
|
||||
}
|
||||
// Now that we know the size of the coming buffer, we can allocate our
|
||||
// buffer and start putting data into it.
|
||||
boost::asio::async_read(
|
||||
|
@ -186,7 +197,7 @@ namespace tcp {
|
|||
message->buffer(),
|
||||
_strand.wrap(handle_read_data));
|
||||
} else {
|
||||
log_warning("streaming client: failed to read header:", ec.message());
|
||||
log_info("streaming client: failed to read header:", ec.message());
|
||||
DEBUG_ONLY(log_debug("size = ", message->size()));
|
||||
DEBUG_ONLY(log_debug("bytes = ", bytes));
|
||||
Connect();
|
||||
|
|
|
@ -8,6 +8,7 @@
|
|||
|
||||
#include "carla/Buffer.h"
|
||||
#include "carla/NonCopyable.h"
|
||||
#include "carla/profiler/LifetimeProfiled.h"
|
||||
#include "carla/streaming/detail/Token.h"
|
||||
#include "carla/streaming/detail/Types.h"
|
||||
|
||||
|
@ -16,6 +17,7 @@
|
|||
#include <boost/asio/ip/tcp.hpp>
|
||||
#include <boost/asio/strand.hpp>
|
||||
|
||||
#include <atomic>
|
||||
#include <functional>
|
||||
#include <memory>
|
||||
|
||||
|
@ -29,9 +31,12 @@ namespace tcp {
|
|||
|
||||
/// A client that connects to a single stream.
|
||||
///
|
||||
/// @warning The client should not be destroyed before the @a io_service is
|
||||
/// stopped.
|
||||
class Client : private NonCopyable {
|
||||
/// @warning This client should be stopped before releasing the shared pointer
|
||||
/// or won't be destroyed.
|
||||
class Client
|
||||
: public std::enable_shared_from_this<Client>,
|
||||
private profiler::LifetimeProfiled,
|
||||
private NonCopyable {
|
||||
public:
|
||||
|
||||
using endpoint = boost::asio::ip::tcp::endpoint;
|
||||
|
@ -45,6 +50,8 @@ namespace tcp {
|
|||
|
||||
~Client();
|
||||
|
||||
void Connect();
|
||||
|
||||
stream_id_type GetStreamId() const {
|
||||
return _token.get_stream_id();
|
||||
}
|
||||
|
@ -53,8 +60,6 @@ namespace tcp {
|
|||
|
||||
private:
|
||||
|
||||
void Connect();
|
||||
|
||||
void Reconnect();
|
||||
|
||||
void ReadData();
|
||||
|
@ -71,7 +76,7 @@ namespace tcp {
|
|||
|
||||
std::shared_ptr<BufferPool> _buffer_pool;
|
||||
|
||||
bool _done = false;
|
||||
std::atomic_bool _done{false};
|
||||
};
|
||||
|
||||
} // namespace tcp
|
||||
|
|
|
@ -26,7 +26,7 @@ namespace tcp {
|
|||
|
||||
auto session = std::make_shared<ServerSession>(_acceptor.get_io_service(), timeout);
|
||||
|
||||
auto handle_query = [=](const error_code &ec) {
|
||||
auto handle_query = [callback, session](const error_code &ec) {
|
||||
if (!ec) {
|
||||
session->Open(callback);
|
||||
} else {
|
||||
|
|
|
@ -20,6 +20,8 @@ namespace streaming {
|
|||
namespace detail {
|
||||
namespace tcp {
|
||||
|
||||
/// @warning This server cannot be destructed before its @a io_service is
|
||||
/// stopped.
|
||||
class Server : private NonCopyable {
|
||||
public:
|
||||
|
||||
|
|
|
@ -24,16 +24,14 @@ namespace tcp {
|
|||
ServerSession::ServerSession(
|
||||
boost::asio::io_service &io_service,
|
||||
const time_duration timeout)
|
||||
: _session_id(SESSION_COUNTER++),
|
||||
: LIBCARLA_INITIALIZE_LIFETIME_PROFILER(
|
||||
std::string("tcp server session ") + std::to_string(SESSION_COUNTER)),
|
||||
_session_id(SESSION_COUNTER++),
|
||||
_socket(io_service),
|
||||
_timeout(timeout),
|
||||
_deadline(io_service),
|
||||
_strand(io_service) {}
|
||||
|
||||
ServerSession::~ServerSession() {
|
||||
_deadline.cancel();
|
||||
}
|
||||
|
||||
void ServerSession::Open(callback_function_type callback) {
|
||||
StartTimer();
|
||||
auto self = shared_from_this(); // To keep myself alive.
|
||||
|
@ -48,7 +46,7 @@ namespace tcp {
|
|||
_socket.get_io_service().post([=]() { cb(self); });
|
||||
} else {
|
||||
log_error("session", _session_id, ": error retrieving stream id :", ec.message());
|
||||
Close();
|
||||
CloseNow();
|
||||
}
|
||||
};
|
||||
|
||||
|
@ -61,23 +59,16 @@ namespace tcp {
|
|||
});
|
||||
}
|
||||
|
||||
void ServerSession::Close() {
|
||||
_strand.post([this, self = shared_from_this()]() {
|
||||
if (_socket.is_open()) {
|
||||
_socket.close();
|
||||
}
|
||||
log_debug("session", _session_id, "closed");
|
||||
});
|
||||
}
|
||||
|
||||
void ServerSession::Write(std::shared_ptr<const Message> message) {
|
||||
DEBUG_ASSERT(message != nullptr);
|
||||
DEBUG_ASSERT(!message->empty());
|
||||
auto self = shared_from_this();
|
||||
_strand.post([=]() {
|
||||
if (!_socket.is_open()) {
|
||||
return;
|
||||
}
|
||||
if (_is_writing) {
|
||||
// Re-post and return;
|
||||
Write(std::move(message));
|
||||
log_debug("session", _session_id, ": connection too slow: message discarded");
|
||||
return;
|
||||
}
|
||||
_is_writing = true;
|
||||
|
@ -85,7 +76,8 @@ namespace tcp {
|
|||
auto handle_sent = [this, self, message](const boost::system::error_code &ec, size_t DEBUG_ONLY(bytes)) {
|
||||
_is_writing = false;
|
||||
if (ec) {
|
||||
log_error("session", _session_id, ": error sending data :", ec.message());
|
||||
log_info("session", _session_id, ": error sending data :", ec.message());
|
||||
CloseNow();
|
||||
} else {
|
||||
DEBUG_ONLY(log_debug("session", _session_id, ": successfully sent", bytes, "bytes"));
|
||||
DEBUG_ASSERT_EQ(bytes, sizeof(message_size_type) + message->size());
|
||||
|
@ -105,14 +97,27 @@ namespace tcp {
|
|||
void ServerSession::StartTimer() {
|
||||
if (_deadline.expires_at() <= boost::asio::deadline_timer::traits_type::now()) {
|
||||
log_debug("session", _session_id, "timed out");
|
||||
Close();
|
||||
_strand.post([self=shared_from_this()]() { self->CloseNow(); });
|
||||
} else {
|
||||
_deadline.async_wait([self = shared_from_this()](boost::system::error_code) {
|
||||
self->StartTimer();
|
||||
_deadline.async_wait([this, self=shared_from_this()](boost::system::error_code ec) {
|
||||
if (!ec) {
|
||||
StartTimer();
|
||||
} else {
|
||||
log_debug("session", _session_id, "timed out error:", ec.message());
|
||||
}
|
||||
});
|
||||
}
|
||||
}
|
||||
|
||||
void ServerSession::CloseNow() {
|
||||
DEBUG_ASSERT(_strand.running_in_this_thread());
|
||||
_deadline.cancel();
|
||||
if (_socket.is_open()) {
|
||||
_socket.close();
|
||||
}
|
||||
log_debug("session", _session_id, "closed");
|
||||
}
|
||||
|
||||
} // namespace tcp
|
||||
} // namespace detail
|
||||
} // namespace streaming
|
||||
|
|
|
@ -9,6 +9,7 @@
|
|||
#include "carla/NonCopyable.h"
|
||||
#include "carla/Time.h"
|
||||
#include "carla/TypeTraits.h"
|
||||
#include "carla/profiler/LifetimeProfiled.h"
|
||||
#include "carla/streaming/detail/Types.h"
|
||||
#include "carla/streaming/detail/tcp/Message.h"
|
||||
|
||||
|
@ -30,6 +31,7 @@ namespace tcp {
|
|||
/// closes itself after @a timeout of inactivity is met.
|
||||
class ServerSession
|
||||
: public std::enable_shared_from_this<ServerSession>,
|
||||
private profiler::LifetimeProfiled,
|
||||
private NonCopyable {
|
||||
public:
|
||||
|
||||
|
@ -38,8 +40,6 @@ namespace tcp {
|
|||
|
||||
explicit ServerSession(boost::asio::io_service &io_service, time_duration timeout);
|
||||
|
||||
~ServerSession();
|
||||
|
||||
/// Starts the session and calls @a callback after successfully reading the
|
||||
/// stream id.
|
||||
void Open(callback_function_type callback);
|
||||
|
@ -59,15 +59,14 @@ namespace tcp {
|
|||
Write(std::make_shared<const Message>(std::move(buffers)...));
|
||||
}
|
||||
|
||||
/// Posts a job to close this session.
|
||||
void Close();
|
||||
|
||||
private:
|
||||
|
||||
void Write(std::shared_ptr<const Message> message);
|
||||
|
||||
void StartTimer();
|
||||
|
||||
void CloseNow();
|
||||
|
||||
friend class Server;
|
||||
|
||||
const size_t _session_id;
|
||||
|
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue