Merge branch 'master' into feature/new_opendrive_parser

This commit is contained in:
nsubiron 2019-03-27 16:40:11 +01:00
commit 560c124dab
26 changed files with 174 additions and 65 deletions

View File

@ -1,5 +1,10 @@
## Latest Changes
* LaneInvasionSensor stabilization
- Fix naming: Use 'LaneInvasionSensor'/'lane_invasion' instead of mixture with 'LaneDetector'/'lane_detector'
- Create server-side LaneInvasionSensor (to be able to access it via ROS bridge)
* Fix ActorList returned by ActorList.Filter(...)
* Add --rolename to manual_control.py
* Migrate Content to AWS
* Adding a parser to represent the map as a connected graph of waypoints.
* Allow user to disable rendering and set the server timeout from the command line
@ -11,12 +16,29 @@
* Fixed python client DLL error on Windows
* Fixed wheel's tire friction from physics control parameters.
* Fixed cleanup of local_planner when used by other modules
* Fixed Obstacle Detector
* New Town07, rural environment with narrow roads
* Added new pack of assets
- Windmill, different farm houses, silo
- Plants corn, dandelion, poppy, and grass
- Yield traffic sign
* Added modular buildings New York style
* Added marking lanes in Town03
* Improved performance in Town01 and Town02
* Changed yellow marking lane from Town01 and Town02 to dashed yellow marking lane
* Fixed semantic segmentation tags in Town04, Town05, Town06
* Fixed tree collision in Town01
* Fixed VehicleSpawnPoint in Town01
* Fixed geo-reference of Town01 and Town07
* Fixed floating pillars in Town04
* Fixed floating building in Town03
* Enhanced stop triggers options
## CARLA 0.9.4
* Added recording and playback functionality
* Added synchronous mode, simulator waits until a client sends a "tick" cue, `client.tick()`
* Allow changing map from client-side, added `client.load_map(name)`, `client.reload_map()`, and `client.get_available_maps()`
* Allow changing map from client-side, added `client.load_world(name)`, `client.reload_world()`, and `client.get_available_maps()`
* Added scripts and tools to import maps directly from .fbx and .xodr files into the simulator
* Exposed minimum physics control parameters for vehicles' engine and wheels
* Allow controlling multiple actors in "batch mode"

View File

@ -48,7 +48,7 @@ This is the list of sensors currently available
* [sensor.camera.semantic_segmentation](#sensorcamerasemantic_segmentation)
* [sensor.lidar.ray_cast](#sensorlidarray_cast)
* [sensor.other.collision](#sensorothercollision)
* [sensor.other.lane_detector](#sensorotherlane_detector)
* [sensor.other.lane_invasion](#sensorotherlane_invasion)
* [sensor.other.obstacle](#sensorotherobstacle)
sensor.camera.rgb
@ -268,14 +268,14 @@ object for each collision registered
Note that several collision events might be registered during a single
simulation update.
sensor.other.lane_detector
sensor.other.lane_invasion
--------------------------
> _This sensor is a work in progress, currently very limited._
This sensor, when attached to an actor, it registers an event each time the
actor crosses a lane marking. This sensor is somehow special as it works fully
on the client-side. The lane detector uses the road data of the active map to
on the client-side. The lane invasion uses the road data of the active map to
determine whether a vehicle is invading another lane. This information is based
on the OpenDrive file provided by the map, therefore it is subject to the
fidelity of the OpenDrive description. In some places there might be

View File

@ -114,20 +114,25 @@
- `get_location()`
- `get_transform()`
- `get_velocity()`
- `get_angular_velocity()`
- `get_acceleration()`
- `set_location(location)`
- `set_transform(transform)`
- `set_velocity(vector)`
- `set_angular_velocity(vector)`
- `add_impulse(vector)`
- `set_simulate_physics(enabled=True)`
- `destroy()`
- `__str__()`
## `carla.Vehicle(carla.Actor)`
- `bounding_box`
- `apply_control(vehicle_control)`
- `get_control()`
- `set_autopilot(enabled=True)`
- `get_physics_control()`
- `apply_physics_control(vehicle_physics_control)`
- `set_autopilot(enabled=True)`
- `get_speed_limit()`
- `get_traffic_light_state()`
- `is_at_traffic_light()`
@ -217,6 +222,8 @@
- `brake`
- `hand_brake`
- `reverse`
- `gear`
- `manual_gear_shift`
- `__eq__(other)`
- `__ne__(other)`

View File

@ -29,7 +29,3 @@ endif ()
if ((LIBCARLA_BUILD_TEST) AND (NOT WIN32))
add_subdirectory("test")
endif()
unset(LIBCARLA_BUILD_TEST CACHE)
unset(LIBCARLA_BUILD_RELEASE CACHE)
unset(LIBCARLA_BUILD_DEBUG CACHE)

View File

@ -29,11 +29,11 @@ namespace client {
return nullptr;
}
ActorList ActorList::Filter(const std::string &wildcard_pattern) const {
ActorList filtered{_episode, {}};
SharedPtr<ActorList> ActorList::Filter(const std::string &wildcard_pattern) const {
SharedPtr<ActorList> filtered (new ActorList(_episode, {}));
for (auto &&actor : _actors) {
if (StringUtil::Match(actor.GetTypeId(), wildcard_pattern)) {
filtered._actors.push_back(actor);
filtered->_actors.push_back(actor);
}
}
return filtered;

View File

@ -31,7 +31,7 @@ namespace client {
SharedPtr<Actor> Find(ActorId actor_id) const;
/// Filters a list of Actor with type id matching @a wildcard_pattern.
ActorList Filter(const std::string &wildcard_pattern) const;
SharedPtr<ActorList> Filter(const std::string &wildcard_pattern) const;
SharedPtr<Actor> operator[](size_t pos) const {
return _actors[pos].Get(_episode, shared_from_this());

View File

@ -60,7 +60,7 @@ namespace client {
_geo_reference.Transform(GetLocation()));
} catch (const std::exception &e) {
/// @todo We need to unsubscribe the sensor.
// log_error("LaneDetector:", e.what());
// log_error("GnssSensor:", e.what());
return nullptr;
}
}

View File

@ -4,7 +4,7 @@
// This work is licensed under the terms of the MIT license.
// For a copy, see <https://opensource.org/licenses/MIT>.
#include "carla/client/LaneDetector.h"
#include "carla/client/LaneInvasionSensor.h"
#include "carla/Logging.h"
#include "carla/client/Map.h"
@ -40,9 +40,9 @@ namespace client {
location + Rotate(yaw, geom::Location(-box.extent.x, -box.extent.y, 0.0f))};
}
LaneDetector::~LaneDetector() = default;
LaneInvasionSensor::~LaneInvasionSensor() = default;
void LaneDetector::Listen(CallbackFunctionType callback) {
void LaneInvasionSensor::Listen(CallbackFunctionType callback) {
if (_is_listening) {
log_error(GetDisplayId(), ": already listening");
return;
@ -57,15 +57,15 @@ namespace client {
_map = GetWorld().GetMap();
DEBUG_ASSERT(_map != nullptr);
auto self = boost::static_pointer_cast<LaneDetector>(shared_from_this());
auto self = boost::static_pointer_cast<LaneInvasionSensor>(shared_from_this());
log_debug(GetDisplayId(), ": subscribing to tick event");
GetEpisode().Lock()->RegisterOnTickEvent([
cb=std::move(callback),
weak_self=WeakPtr<LaneDetector>(self)](const auto &timestamp) {
weak_self=WeakPtr<LaneInvasionSensor>(self)](const auto &timestamp) {
auto self = weak_self.lock();
if (self != nullptr) {
auto data = self->TickLaneDetector(timestamp);
auto data = self->TickLaneInvasionSensor(timestamp);
if (data != nullptr) {
cb(std::move(data));
}
@ -74,11 +74,12 @@ namespace client {
_is_listening = true;
}
void LaneDetector::Stop() {
throw_exception(std::runtime_error("LaneDetector::Stop(): not implemented."));
void LaneInvasionSensor::Stop() {
/// @todo We need unsubscribe from the world on tick.
_is_listening = false;
}
SharedPtr<sensor::SensorData> LaneDetector::TickLaneDetector(
SharedPtr<sensor::SensorData> LaneInvasionSensor::TickLaneInvasionSensor(
const Timestamp &timestamp) {
try {
const auto new_bounds = GetVehicleBounds(*_vehicle);
@ -98,7 +99,7 @@ namespace client {
crossed_lanes);
} catch (const std::exception &e) {
/// @todo We need to unsubscribe the sensor.
// log_error("LaneDetector:", e.what());
// log_error("LaneInvasionSensor:", e.what());
return nullptr;
}
}

View File

@ -17,12 +17,12 @@ namespace client {
class Map;
class Vehicle;
class LaneDetector final : public ClientSideSensor {
class LaneInvasionSensor final : public ClientSideSensor {
public:
using ClientSideSensor::ClientSideSensor;
~LaneDetector();
~LaneInvasionSensor();
/// Register a @a callback to be executed each time a new measurement is
/// received.
@ -43,7 +43,7 @@ namespace client {
private:
SharedPtr<sensor::SensorData> TickLaneDetector(const Timestamp &timestamp);
SharedPtr<sensor::SensorData> TickLaneInvasionSensor(const Timestamp &timestamp);
bool _is_listening = false;

View File

@ -10,7 +10,7 @@
#include "carla/StringUtil.h"
#include "carla/client/Actor.h"
#include "carla/client/GnssSensor.h"
#include "carla/client/LaneDetector.h"
#include "carla/client/LaneInvasionSensor.h"
#include "carla/client/ServerSideSensor.h"
#include "carla/client/TrafficLight.h"
#include "carla/client/TrafficSign.h"
@ -73,8 +73,8 @@ namespace detail {
SharedPtr<Actor> parent,
GarbageCollectionPolicy gc) {
auto init = ActorInitializer{description, episode, parent};
if (description.description.id == "sensor.other.lane_detector") { /// @todo
return MakeActorImpl<LaneDetector>(std::move(init), gc);
if (description.description.id == "sensor.other.lane_invasion") { /// @todo
return MakeActorImpl<LaneInvasionSensor>(std::move(init), gc);
} else if (description.description.id == "sensor.other.gnss") { /// @todo
return MakeActorImpl<GnssSensor>(std::move(init), gc);
} else if (description.HasAStream()) {

View File

@ -111,12 +111,6 @@ namespace detail {
SharedPtr<BlueprintLibrary> Simulator::GetBlueprintLibrary() {
auto defs = _client.GetActorDefinitions();
{ /// @todo
rpc::ActorDefinition def;
def.id = "sensor.other.lane_detector";
def.tags = "sensor,other,lane_detector";
defs.emplace_back(def);
}
return MakeShared<BlueprintLibrary>(std::move(defs));
}
@ -138,9 +132,7 @@ namespace detail {
Actor *parent,
GarbageCollectionPolicy gc) {
rpc::Actor actor;
if (blueprint.GetId() == "sensor.other.lane_detector") { /// @todo
actor.description = blueprint.MakeActorDescription();
} else if (parent != nullptr) {
if (parent != nullptr) {
actor = _client.SpawnActorWithParent(
blueprint.MakeActorDescription(),
transform,
@ -165,9 +157,7 @@ namespace detail {
bool Simulator::DestroyActor(Actor &actor) {
bool success = true;
if (actor.GetTypeId() != "sensor.other.lane_detector") { /// @todo
success = _client.DestroyActor(actor.GetId());
}
success = _client.DestroyActor(actor.GetId());
if (success) {
// Remove it's persistent state so it cannot access the client anymore.
actor.GetEpisode().Clear();

View File

@ -24,6 +24,7 @@
class ACollisionSensor;
class ADepthCamera;
class AGnssSensor;
class ALaneInvasionSensor;
class AObstacleDetectionSensor;
class ARayCastLidar;
class ASceneCaptureCamera;
@ -45,6 +46,7 @@ namespace sensor {
std::pair<ARayCastLidar *, s11n::LidarSerializer>,
std::pair<ACollisionSensor *, s11n::CollisionEventSerializer>,
std::pair<AGnssSensor *, s11n::ImageSerializer>,
std::pair<ALaneInvasionSensor *, s11n::ImageSerializer>,
std::pair<AObstacleDetectionSensor *, s11n::ObstacleDetectionEventSerializer>
>;
@ -63,6 +65,7 @@ namespace sensor {
#include "Carla/Sensor/SemanticSegmentationCamera.h"
#include "Carla/Sensor/WorldObserver.h"
#include "Carla/Sensor/GnssSensor.h"
#include "Carla/Sensor/LaneInvasionSensor.h"
#include "Carla/Sensor/ObstacleDetectionSensor.h"
#endif // LIBCARLA_SENSOR_REGISTRY_WITH_SENSOR_INCLUDES

View File

@ -572,7 +572,7 @@ class LaneInvasionSensor(object):
self._parent = parent_actor
self.hud = hud
world = self._parent.get_world()
bp = world.get_blueprint_library().find('sensor.other.lane_detector')
bp = world.get_blueprint_library().find('sensor.other.lane_invasion')
self.sensor = world.spawn_actor(bp, carla.Transform(), attach_to=self._parent)
# We need to pass the lambda a weak reference to self to avoid circular
# reference.

View File

@ -143,8 +143,9 @@ def get_actor_display_name(actor, truncate=250):
class World(object):
def __init__(self, carla_world, hud, actor_filter):
def __init__(self, carla_world, hud, actor_filter, actor_role_name='hero'):
self.world = carla_world
self.actor_role_name = actor_role_name
self.map = self.world.get_map()
self.hud = hud
self.player = None
@ -166,7 +167,7 @@ class World(object):
cam_pos_index = self.camera_manager.transform_index if self.camera_manager is not None else 0
# Get a random blueprint.
blueprint = random.choice(self.world.get_blueprint_library().filter(self._actor_filter))
blueprint.set_attribute('role_name', 'hero')
blueprint.set_attribute('role_name', self.actor_role_name)
if blueprint.has_attribute('color'):
color = random.choice(blueprint.get_attribute('color').recommended_values)
blueprint.set_attribute('color', color)
@ -604,7 +605,7 @@ class LaneInvasionSensor(object):
self._parent = parent_actor
self.hud = hud
world = self._parent.get_world()
bp = world.get_blueprint_library().find('sensor.other.lane_detector')
bp = world.get_blueprint_library().find('sensor.other.lane_invasion')
self.sensor = world.spawn_actor(bp, carla.Transform(), attach_to=self._parent)
# We need to pass the lambda a weak reference to self to avoid circular
# reference.
@ -767,7 +768,7 @@ def game_loop(args):
pygame.HWSURFACE | pygame.DOUBLEBUF)
hud = HUD(args.width, args.height)
world = World(client.get_world(), hud, args.filter)
world = World(client.get_world(), hud, args.filter, args.rolename)
controller = KeyboardControl(world, args.autopilot)
clock = pygame.time.Clock()
@ -828,6 +829,11 @@ def main():
metavar='PATTERN',
default='vehicle.*',
help='actor filter (default: "vehicle.*")')
argparser.add_argument(
'--rolename',
metavar='NAME',
default='hero',
help='actor role name (default: "hero")')
args = argparser.parse_args()
args.width, args.height = [int(x) for x in args.res.split('x')]

View File

@ -617,7 +617,7 @@ class LaneInvasionSensor(object):
self._parent = parent_actor
self.hud = hud
world = self._parent.get_world()
bp = world.get_blueprint_library().find('sensor.other.lane_detector')
bp = world.get_blueprint_library().find('sensor.other.lane_invasion')
self.sensor = world.spawn_actor(bp, carla.Transform(), attach_to=self._parent)
# We need to pass the lambda a weak reference to self to avoid circular
# reference.

View File

@ -16,7 +16,7 @@ import os
import sys
try:
sys.path.append(glob.glob('../**/carla-*%d.%d-%s.egg' % (
sys.path.append(glob.glob('**/carla-*%d.%d-%s.egg' % (
sys.version_info.major,
sys.version_info.minor,
'win-amd64' if os.name == 'nt' else 'linux-x86_64'))[0])
@ -157,6 +157,7 @@ def get_dynamic_objects(carla_world, carla_map):
speed_limits = []
walkers = []
stops = []
static_obstacles = []
for actor in actors:
if 'vehicle' in actor.type_id:
vehicles.append(actor)
@ -168,7 +169,11 @@ def get_dynamic_objects(carla_world, carla_map):
walkers.append(actor)
elif 'stop' in actor.type_id:
stops.append(actor)
return (vehicles, traffic_lights, speed_limits, walkers, stops)
elif 'static.prop' in actor.type_id:
static_obstacles.append(actor)
return (vehicles, traffic_lights, speed_limits, walkers, stops, static_obstacles)
# Public functions
def get_stop_signals(stops):
@ -255,8 +260,20 @@ def get_dynamic_objects(carla_world, carla_map):
speed_limits_dict[speed_limit.id] = sl_dict
return speed_limits_dict
def get_static_obstacles(static_obstacles):
static_obstacles_dict = dict()
for static_prop in static_obstacles:
sl_transform = static_prop.get_transform()
location_gnss = carla_map.transform_to_geolocation(sl_transform.location)
sl_dict = {
"id": static_prop.id,
"position": [location_gnss.latitude, location_gnss.longitude, location_gnss.altitude]
}
static_obstacles_dict[static_prop.id] = sl_dict
return static_obstacles_dict
actors = carla_world.get_actors()
vehicles, traffic_lights, speed_limits, walkers, stops = _split_actors(actors)
vehicles, traffic_lights, speed_limits, walkers, stops, static_obstacles = _split_actors(actors)
hero_vehicles = [vehicle for vehicle in vehicles if
'vehicle' in vehicle.type_id and vehicle.attributes['role_name'] == 'hero']
@ -268,5 +285,6 @@ def get_dynamic_objects(carla_world, carla_map):
'walkers': get_walkers(walkers),
'traffic_lights': get_traffic_lights(traffic_lights),
'stop_signs': get_stop_signals(stops),
'speed_limits': get_speed_limits(speed_limits)
'speed_limits': get_speed_limits(speed_limits),
'static_obstacles': get_static_obstacles(static_obstacles)
}

View File

@ -7,7 +7,7 @@
#include <carla/PythonUtil.h>
#include <carla/client/ClientSideSensor.h>
#include <carla/client/GnssSensor.h>
#include <carla/client/LaneDetector.h>
#include <carla/client/LaneInvasionSensor.h>
#include <carla/client/Sensor.h>
#include <carla/client/ServerSideSensor.h>
@ -36,8 +36,8 @@ void export_sensor() {
.def(self_ns::str(self_ns::self))
;
class_<cc::LaneDetector, bases<cc::ClientSideSensor>, boost::noncopyable, boost::shared_ptr<cc::LaneDetector>>
("LaneDetector", no_init)
class_<cc::LaneInvasionSensor, bases<cc::ClientSideSensor>, boost::noncopyable, boost::shared_ptr<cc::LaneInvasionSensor>>
("LaneInvasionSensor", no_init)
.def(self_ns::str(self_ns::self))
;

View File

@ -24,8 +24,7 @@ If you want to benchmark your model in the same conditions as in our CoRL17
paper, check out
[Benchmarking](https://github.com/carla-simulator/driving-benchmarks).
[**Get CARLA overnight build**](http://158.109.9.218:8080/job/carla/job/master/25/artifact/Dist/CARLA_eff21e2.tar.gz)
[**Get CARLA overnight build**](http://carla-assets-internal.s3.amazonaws.com/Releases/Linux/Dev/CARLA_Latest.tar.gz)
## CARLA Ecosystem
Repositories associated to the CARLA simulation platform:
@ -33,7 +32,7 @@ Repositories associated to the CARLA simulation platform:
* [**Scenario_Runner**](https://github.com/carla-simulator/scenario_runner): Engine to execute traffic scenarios in CARLA 0.9.X
* [**ROS-bridge**](https://github.com/carla-simulator/ros-bridge): Interface to connect CARLA 0.9.X to ROS
* [**Driving-benchmarks**](https://github.com/carla-simulator/driving-benchmarks): Benchmark tools for Autonomous Driving tasks
* [**Conditional Imitation-Learning**](https://github.com/felipecode/coiltraine): Training and testing Conditional Imitation Learning models in CARLA [README](https://github.com/felipecode/coiltraine/blob/master/docs/view_agents.md)
* [**Conditional Imitation-Learning**](https://github.com/felipecode/coiltraine): Training and testing Conditional Imitation Learning models in CARLA
* [**AutoWare AV stack**](https://github.com/carla-simulator/carla-autoware): Bridge to connect AutoWare AV stack to CARLA
* [**Reinforcement-Learning**](https://github.com/carla-simulator/reinforcement-learning): Code for running Conditional Reinforcement Learning models in CARLA
* [**Map Editor**](https://github.com/carla-simulator/carla-map-editor): Standalone GUI application to enhance RoadRunner maps with traffic lights and traffic signs information

View File

@ -0,0 +1,26 @@
// Copyright (c) 2019 Intel Labs.
//
// This work is licensed under the terms of the MIT license.
// For a copy, see <https://opensource.org/licenses/MIT>.
#include "Carla.h"
#include "Carla/Sensor/LaneInvasionSensor.h"
#include "StaticMeshResources.h"
FActorDefinition ALaneInvasionSensor::GetSensorDefinition()
{
return UActorBlueprintFunctionLibrary::MakeGenericSensorDefinition(TEXT("other"), TEXT("lane_invasion"));
}
ALaneInvasionSensor::ALaneInvasionSensor(const FObjectInitializer &ObjectInitializer)
: Super(ObjectInitializer)
{
PrimaryActorTick.bCanEverTick = false;
auto MeshComp = CreateDefaultSubobject<UStaticMeshComponent>(TEXT("RootComponent"));
MeshComp->SetCollisionProfileName(UCollisionProfile::NoCollision_ProfileName);
MeshComp->bHiddenInGame = true;
MeshComp->CastShadow = false;
MeshComp->PostPhysicsComponentTick.bCanEverTick = false;
RootComponent = MeshComp;
}

View File

@ -0,0 +1,27 @@
// Copyright (c) 2019 Intel Labs.
//
// This work is licensed under the terms of the MIT license.
// For a copy, see <https://opensource.org/licenses/MIT>.
#pragma once
#include "Carla/Sensor/ShaderBasedSensor.h"
#include "Carla/Actor/ActorDefinition.h"
#include "LaneInvasionSensor.generated.h"
/// LaneInvasion sensor representation
/// The actual position calculation is done one client side
UCLASS()
class CARLA_API ALaneInvasionSensor : public ASensor
{
GENERATED_BODY()
public:
static FActorDefinition GetSensorDefinition();
ALaneInvasionSensor(const FObjectInitializer &ObjectInitializer);
};

View File

@ -17,6 +17,13 @@ AObstacleDetectionSensor::AObstacleDetectionSensor(const FObjectInitializer &Obj
: Super(ObjectInitializer)
{
PrimaryActorTick.bCanEverTick = true;
auto MeshComp = CreateDefaultSubobject<UStaticMeshComponent>(TEXT("RootComponent"));
MeshComp->SetCollisionProfileName(UCollisionProfile::NoCollision_ProfileName);
MeshComp->bHiddenInGame = true;
MeshComp->CastShadow = false;
MeshComp->PostPhysicsComponentTick.bCanEverTick = false;
RootComponent = MeshComp;
}
FActorDefinition AObstacleDetectionSensor::GetSensorDefinition()

View File

@ -63,11 +63,12 @@ function download_content {
aria2c -j16 -x16 --input-file=.aria2c.input
rm -f .aria2c.input
else
wget ${CONTENT_LINK} Content.tar.gz
wget ${CONTENT_LINK} -O Content.tar.gz
fi
tar -xvzf Content.tar.gz -C Content
rm Content.tar.gz
mv Content/* $CONTENT_FOLDER
rm -rf Content
echo "$CONTENT_ID" > "$VERSION_FILE"
echo "Content updated successfully."
}

View File

@ -107,12 +107,15 @@ if $DO_COPY_FILES ; then
copy_if_changed "./PythonAPI/manual_control.py" "${DESTINATION}/manual_control.py"
copy_if_changed "./PythonAPI/no_rendering_mode.py" "${DESTINATION}/no_rendering_mode.py"
copy_if_changed "./PythonAPI/performance_benchmark.py" "${DESTINATION}/performance_benchmark.py"
copy_if_changed "./PythonAPI/scene_layout.py" "${DESTINATION}/scene_layout.py"
copy_if_changed "./PythonAPI/spawn_npc.py" "${DESTINATION}/spawn_npc.py"
copy_if_changed "./PythonAPI/synchronous_mode.py" "${DESTINATION}/synchronous_mode.py"
copy_if_changed "./PythonAPI/tutorial.py" "${DESTINATION}/tutorial.py"
copy_if_changed "./PythonAPI/vehicle_gallery.py" "${DESTINATION}/vehicle_gallery.py"
copy_if_changed "./Util/ImportMaps.sh" "${DESTINATION}/ImportMaps.sh"
echo "${REPOSITORY_TAG}" > ${DESTINATION}/VERSION
popd >/dev/null
fi

View File

@ -184,10 +184,11 @@ set CMAKE_CONFIG_FILE="%INSTALLATION_DIR%CMakeLists.txt.in"
>"%CMAKE_CONFIG_FILE%" echo # Automatically generated by Setup.bat
>>"%CMAKE_CONFIG_FILE%" echo set(CARLA_VERSION %carla_version%)
>>"%CMAKE_CONFIG_FILE%" echo.
>>"%CMAKE_CONFIG_FILE%" echo if (WIN32)
>>"%CMAKE_CONFIG_FILE%" echo add_definitions(-D_WIN32_WINNT=0x0501)
>>"%CMAKE_CONFIG_FILE%" echo STRING (REGEX REPLACE "/RTC(su|[1su])" "" CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}")
>>"%CMAKE_CONFIG_FILE%" echo endif()
>>"%CMAKE_CONFIG_FILE%" echo set(CMAKE_CXX_STANDARD 14)
>>"%CMAKE_CONFIG_FILE%" echo set(CMAKE_CXX_STANDARD_REQUIRED ON)
>>"%CMAKE_CONFIG_FILE%" echo.
>>"%CMAKE_CONFIG_FILE%" echo add_definitions(-D_WIN32_WINNT=0x0501)
>>"%CMAKE_CONFIG_FILE%" echo STRING (REGEX REPLACE "/RTC(su|[1su])" "" CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}")
>>"%CMAKE_CONFIG_FILE%" echo.
>>"%CMAKE_CONFIG_FILE%" echo add_definitions(-DBOOST_ERROR_CODE_HEADER_ONLY)
>>"%CMAKE_CONFIG_FILE%" echo add_definitions(-DLIBCARLA_IMAGE_WITH_PNG_SUPPORT)
@ -200,6 +201,8 @@ set CMAKE_CONFIG_FILE="%INSTALLATION_DIR%CMakeLists.txt.in"
>>"%CMAKE_CONFIG_FILE%" echo.
>>"%CMAKE_CONFIG_FILE%" echo if (CMAKE_BUILD_TYPE STREQUAL "Server")
>>"%CMAKE_CONFIG_FILE%" echo # Prevent exceptions
>>"%CMAKE_CONFIG_FILE%" echo add_compile_options(/GR-)
>>"%CMAKE_CONFIG_FILE%" echo add_compile_options(/EHsc)
>>"%CMAKE_CONFIG_FILE%" echo add_definitions(-DASIO_NO_EXCEPTIONS)
>>"%CMAKE_CONFIG_FILE%" echo add_definitions(-DBOOST_NO_EXCEPTIONS)
>>"%CMAKE_CONFIG_FILE%" echo add_definitions(-DLIBCARLA_NO_EXCEPTIONS)

View File

@ -325,7 +325,7 @@ cat >>${LIBCPP_TOOLCHAIN_FILE}.gen <<EOL
set(CMAKE_CXX_FLAGS "\${CMAKE_CXX_FLAGS} -stdlib=libc++" CACHE STRING "" FORCE)
set(CMAKE_CXX_FLAGS "\${CMAKE_CXX_FLAGS} -I${LLVM_INCLUDE}" CACHE STRING "" FORCE)
set(CMAKE_CXX_FLAGS "\${CMAKE_CXX_FLAGS} -fno-exceptions" CACHE STRING "" FORCE)
set(CMAKE_CXX_FLAGS "\${CMAKE_CXX_FLAGS} -fno-exceptions -fno-rtti" CACHE STRING "" FORCE)
set(CMAKE_CXX_LINK_FLAGS "\${CMAKE_CXX_LINK_FLAGS} -L${LLVM_LIBPATH}" CACHE STRING "" FORCE)
set(CMAKE_CXX_LINK_FLAGS "\${CMAKE_CXX_LINK_FLAGS} -lc++ -lc++abi" CACHE STRING "" FORCE)
EOL

View File

@ -27,4 +27,4 @@
#
# http://carla-assets-internal.s3.amazonaws.com/Content/PUT_FILE_ID_HERE.tar.gz
Latest: 20190319_7f836a8
Latest: 20190327_f6c9b01