diff --git a/CHANGELOG.md b/CHANGELOG.md index f4672927e..4b307d469 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,7 +1,14 @@ ## Latest Changes * Prevent from segfault on failing SignalReference identification when loading OpenDrive files - * Added vehicle doors to the recorder + * Added vehicle doors to the recorder * Added functions to get actor' components transform + * Added posibility to Digital Twins to work with local files (osm and xodr) + * Enable proper material merging for Building in Digital Twins + * Added functions to get actor' bones transforms + * Added functions to get actor' bones and components names + * Added functions to get actor' sockets transforms + * make PythonAPI Windows: Fixed incompatibility issue with Anaconda due `py` command. + * Fixed bug in python agents when vehicle list was empty causing a check on all vehicles (BasicAgent.py) and detected pedestrians as vehicles if no pedestrains are present (BehaviourAgent.py) ## CARLA 0.9.15 diff --git a/Docs/build_faq.md b/Docs/build_faq.md index 27ce114dc..07dcc4ada 100644 --- a/Docs/build_faq.md +++ b/Docs/build_faq.md @@ -365,7 +365,7 @@ CARLA forum >In Windows it will be the default Python version for: -> py -3 --version +> python --version >Make sure you are running your scripts with the version of Python that corresponds to your `.egg` file. >In Linux, you may also need to set your Python path to point to the CARLA `.egg`. To do this, run the following command: diff --git a/LibCarla/source/carla/client/Actor.cpp b/LibCarla/source/carla/client/Actor.cpp index cfddf041b..0d2b7f962 100644 --- a/LibCarla/source/carla/client/Actor.cpp +++ b/LibCarla/source/carla/client/Actor.cpp @@ -40,6 +40,30 @@ namespace client { return GetEpisode().Lock()->GetActorComponentRelativeTransform(*this, componentName); } + std::vector Actor::GetBoneWorldTransforms() const { + return GetEpisode().Lock()->GetActorBoneWorldTransforms(*this); + } + + std::vector Actor::GetBoneRelativeTransforms() const { + return GetEpisode().Lock()->GetActorBoneRelativeTransforms(*this); + } + + std::vector Actor::GetComponentNames() const { + return GetEpisode().Lock()->GetActorComponentNames(*this); + } + + std::vector Actor::GetBoneNames() const { + return GetEpisode().Lock()->GetActorBoneNames(*this); + } + + std::vector Actor::GetSocketWorldTransforms() const { + return GetEpisode().Lock()->GetActorSocketWorldTransforms(*this); + } + + std::vector Actor::GetSocketRelativeTransforms() const { + return GetEpisode().Lock()->GetActorSocketRelativeTransforms(*this); + } + void Actor::SetLocation(const geom::Location &location) { GetEpisode().Lock()->SetActorLocation(*this, location); } diff --git a/LibCarla/source/carla/client/Actor.h b/LibCarla/source/carla/client/Actor.h index 79d757468..4afd48d4a 100644 --- a/LibCarla/source/carla/client/Actor.h +++ b/LibCarla/source/carla/client/Actor.h @@ -64,6 +64,18 @@ namespace client { geom::Transform GetComponentRelativeTransform(const std::string componentName) const; + std::vector GetBoneWorldTransforms() const; + + std::vector GetBoneRelativeTransforms() const; + + std::vector GetComponentNames() const; + + std::vector GetBoneNames() const; + + std::vector GetSocketWorldTransforms() const; + + std::vector GetSocketRelativeTransforms() const; + /// Teleport the actor to @a location. void SetLocation(const geom::Location &location); diff --git a/LibCarla/source/carla/client/World.cpp b/LibCarla/source/carla/client/World.cpp index 2855f7f1d..cdda8a513 100644 --- a/LibCarla/source/carla/client/World.cpp +++ b/LibCarla/source/carla/client/World.cpp @@ -119,17 +119,19 @@ namespace client { const ActorBlueprint &blueprint, const geom::Transform &transform, Actor *parent_actor, - rpc::AttachmentType attachment_type) { - return _episode.Lock()->SpawnActor(blueprint, transform, parent_actor, attachment_type); + rpc::AttachmentType attachment_type, + const std::string& socket_name) { + return _episode.Lock()->SpawnActor(blueprint, transform, parent_actor, attachment_type, GarbageCollectionPolicy::Inherit, socket_name); } SharedPtr World::TrySpawnActor( const ActorBlueprint &blueprint, const geom::Transform &transform, Actor *parent_actor, - rpc::AttachmentType attachment_type) noexcept { + rpc::AttachmentType attachment_type, + const std::string& socket_name) noexcept { try { - return SpawnActor(blueprint, transform, parent_actor, attachment_type); + return SpawnActor(blueprint, transform, parent_actor, attachment_type, socket_name); } catch (const std::exception &) { return nullptr; } diff --git a/LibCarla/source/carla/client/World.h b/LibCarla/source/carla/client/World.h index 003fadb26..d8ba32e3e 100644 --- a/LibCarla/source/carla/client/World.h +++ b/LibCarla/source/carla/client/World.h @@ -29,6 +29,7 @@ #include "carla/rpc/Texture.h" #include "carla/rpc/MaterialParameter.h" +#include #include namespace carla { @@ -112,7 +113,8 @@ namespace client { const ActorBlueprint &blueprint, const geom::Transform &transform, Actor *parent = nullptr, - rpc::AttachmentType attachment_type = rpc::AttachmentType::Rigid); + rpc::AttachmentType attachment_type = rpc::AttachmentType::Rigid, + const std::string& socket_name = ""); /// Same as SpawnActor but return nullptr on failure instead of throwing an /// exception. @@ -120,7 +122,8 @@ namespace client { const ActorBlueprint &blueprint, const geom::Transform &transform, Actor *parent = nullptr, - rpc::AttachmentType attachment_type = rpc::AttachmentType::Rigid) noexcept; + rpc::AttachmentType attachment_type = rpc::AttachmentType::Rigid, + const std::string& socket_name = "") noexcept; /// Block calling thread until a world tick is received. WorldSnapshot WaitForTick(time_duration timeout) const; diff --git a/LibCarla/source/carla/client/detail/Client.cpp b/LibCarla/source/carla/client/detail/Client.cpp index 2cf28c7ef..edb148517 100644 --- a/LibCarla/source/carla/client/detail/Client.cpp +++ b/LibCarla/source/carla/client/detail/Client.cpp @@ -326,11 +326,12 @@ namespace detail { return _pimpl->CallAndWait("spawn_actor", description, transform); } - rpc::Actor Client::SpawnActorWithParent( + rpc::Actor Client::SpawnActorWithParent( const rpc::ActorDescription &description, const geom::Transform &transform, rpc::ActorId parent, - rpc::AttachmentType attachment_type) { + rpc::AttachmentType attachment_type, + const std::string& socket_name) { if (attachment_type == rpc::AttachmentType::SpringArm || attachment_type == rpc::AttachmentType::SpringArmGhost) @@ -348,7 +349,8 @@ namespace detail { description, transform, parent, - attachment_type); + attachment_type, + socket_name); } bool Client::DestroyActor(rpc::ActorId actor) { @@ -416,6 +418,36 @@ namespace detail { return _pimpl->CallAndWait("get_actor_component_relative_transform", actor, componentName); } + std::vector Client::GetActorBoneWorldTransforms(rpc::ActorId actor) { + using return_t = std::vector; + return _pimpl->CallAndWait("get_actor_bone_world_transforms", actor); + } + + std::vector Client::GetActorBoneRelativeTransforms(rpc::ActorId actor) { + using return_t = std::vector; + return _pimpl->CallAndWait("get_actor_bone_relative_transforms", actor); + } + + std::vector Client::GetActorComponentNames(rpc::ActorId actor) { + using return_t = std::vector; + return _pimpl->CallAndWait("get_actor_component_names", actor); + } + + std::vector Client::GetActorBoneNames(rpc::ActorId actor) { + using return_t = std::vector; + return _pimpl->CallAndWait("get_actor_bone_names", actor); + } + + std::vector Client::GetActorSocketWorldTransforms(rpc::ActorId actor) { + using return_t = std::vector; + return _pimpl->CallAndWait("get_actor_socket_world_transforms", actor); + } + + std::vector Client::GetActorSocketRelativeTransforms(rpc::ActorId actor) { + using return_t = std::vector; + return _pimpl->CallAndWait("get_actor_socket_relative_transforms", actor); + } + void Client::SetActorSimulatePhysics(rpc::ActorId actor, const bool enabled) { _pimpl->CallAndWait("set_actor_simulate_physics", actor, enabled); } diff --git a/LibCarla/source/carla/client/detail/Client.h b/LibCarla/source/carla/client/detail/Client.h index 0327adbb6..0eff68b6e 100644 --- a/LibCarla/source/carla/client/detail/Client.h +++ b/LibCarla/source/carla/client/detail/Client.h @@ -88,7 +88,6 @@ namespace detail { void DestroyTrafficManager(uint16_t port) const; - void SetTimeout(time_duration timeout); time_duration GetTimeout() const; @@ -180,7 +179,8 @@ namespace detail { const rpc::ActorDescription &description, const geom::Transform &transform, rpc::ActorId parent, - rpc::AttachmentType attachment_type); + rpc::AttachmentType attachment_type, + const std::string& socket_name = ""); bool DestroyActor(rpc::ActorId actor); @@ -241,6 +241,24 @@ namespace detail { rpc::ActorId actor, const std::string componentName); + std::vector GetActorBoneWorldTransforms( + rpc::ActorId actor); + + std::vector GetActorBoneRelativeTransforms( + rpc::ActorId actor); + + std::vector GetActorComponentNames( + rpc::ActorId actor); + + std::vector GetActorBoneNames( + rpc::ActorId actor); + + std::vector GetActorSocketWorldTransforms( + rpc::ActorId actor); + + std::vector GetActorSocketRelativeTransforms( + rpc::ActorId actor); + void SetActorSimulatePhysics( rpc::ActorId actor, bool enabled); diff --git a/LibCarla/source/carla/client/detail/Simulator.cpp b/LibCarla/source/carla/client/detail/Simulator.cpp index ec2fbfae3..28eb8be68 100644 --- a/LibCarla/source/carla/client/detail/Simulator.cpp +++ b/LibCarla/source/carla/client/detail/Simulator.cpp @@ -342,19 +342,21 @@ EpisodeProxy Simulator::GetCurrentEpisode() { // -- General operations with actors ----------------------------------------- // =========================================================================== - SharedPtr Simulator::SpawnActor( + SharedPtr Simulator::SpawnActor( const ActorBlueprint &blueprint, const geom::Transform &transform, Actor *parent, rpc::AttachmentType attachment_type, - GarbageCollectionPolicy gc) { + GarbageCollectionPolicy gc, + const std::string& socket_name) { rpc::Actor actor; if (parent != nullptr) { actor = _client.SpawnActorWithParent( blueprint.MakeActorDescription(), transform, parent->GetId(), - attachment_type); + attachment_type, + socket_name); } else { actor = _client.SpawnActor( blueprint.MakeActorDescription(), diff --git a/LibCarla/source/carla/client/detail/Simulator.h b/LibCarla/source/carla/client/detail/Simulator.h index 76981d4e3..5f8a2ec06 100644 --- a/LibCarla/source/carla/client/detail/Simulator.h +++ b/LibCarla/source/carla/client/detail/Simulator.h @@ -357,7 +357,8 @@ namespace detail { const geom::Transform &transform, Actor *parent = nullptr, rpc::AttachmentType attachment_type = rpc::AttachmentType::Rigid, - GarbageCollectionPolicy gc = GarbageCollectionPolicy::Inherit); + GarbageCollectionPolicy gc = GarbageCollectionPolicy::Inherit, + const std::string& socket_name = ""); bool DestroyActor(Actor &actor); @@ -446,6 +447,30 @@ namespace detail { return _client.GetActorComponentRelativeTransform(actor.GetId(), componentName); } + std::vector GetActorBoneWorldTransforms(const Actor &actor) { + return _client.GetActorBoneWorldTransforms(actor.GetId()); + } + + std::vector GetActorBoneRelativeTransforms(const Actor &actor) { + return _client.GetActorBoneRelativeTransforms(actor.GetId()); + } + + std::vector GetActorComponentNames(const Actor &actor) { + return _client.GetActorComponentNames(actor.GetId()); + } + + std::vector GetActorBoneNames(const Actor &actor) { + return _client.GetActorBoneNames(actor.GetId()); + } + + std::vector GetActorSocketWorldTransforms(const Actor &actor) { + return _client.GetActorSocketWorldTransforms(actor.GetId()); + } + + std::vector GetActorSocketRelativeTransforms(const Actor &actor) { + return _client.GetActorSocketRelativeTransforms(actor.GetId()); + } + void SetActorLocation(Actor &actor, const geom::Location &location) { _client.SetActorLocation(actor.GetId(), location); } diff --git a/LibCarla/source/carla/road/Map.cpp b/LibCarla/source/carla/road/Map.cpp index 70bedbeee..282452c66 100644 --- a/LibCarla/source/carla/road/Map.cpp +++ b/LibCarla/source/carla/road/Map.cpp @@ -1238,7 +1238,11 @@ namespace road { geom::Transform lanetransform = lane->ComputeTransform(s_current); geom::Transform treeTransform(treeposition, lanetransform.rotation); const carla::road::element::RoadInfoSpeed* roadinfo = lane->GetInfo(s_current); - transforms.push_back(std::make_pair(treeTransform,roadinfo->GetType())); + if(roadinfo){ + transforms.push_back(std::make_pair(treeTransform, roadinfo->GetType())); + }else{ + transforms.push_back(std::make_pair(treeTransform, "urban")); + } } s_current += distancebetweentrees; } diff --git a/LibCarla/source/carla/rpc/Command.h b/LibCarla/source/carla/rpc/Command.h index 299c8ad0b..663654e88 100644 --- a/LibCarla/source/carla/rpc/Command.h +++ b/LibCarla/source/carla/rpc/Command.h @@ -10,6 +10,7 @@ #include "carla/MsgPackAdaptors.h" #include "carla/geom/Transform.h" #include "carla/rpc/ActorDescription.h" +#include "carla/rpc/AttachmentType.h" #include "carla/rpc/ActorId.h" #include "carla/rpc/TrafficLightState.h" #include "carla/rpc/VehicleAckermannControl.h" @@ -18,6 +19,8 @@ #include "carla/rpc/VehicleLightState.h" #include "carla/rpc/WalkerControl.h" +#include + #ifdef _MSC_VER #pragma warning(push) #pragma warning(disable:4583) @@ -59,11 +62,19 @@ namespace rpc { : description(std::move(description)), transform(transform), parent(parent) {} + SpawnActor(ActorDescription description, const geom::Transform &transform, ActorId parent, AttachmentType attachment_type, const std::string& bone) + : description(std::move(description)), + transform(transform), + parent(parent), + attachment_type(attachment_type), + socket_name(bone) {} ActorDescription description; geom::Transform transform; boost::optional parent; + AttachmentType attachment_type; + std::string socket_name; std::vector do_after; - MSGPACK_DEFINE_ARRAY(description, transform, parent, do_after); + MSGPACK_DEFINE_ARRAY(description, transform, parent, attachment_type, socket_name, do_after); }; struct DestroyActor : CommandBase { diff --git a/PythonAPI/carla/agents/navigation/basic_agent.py b/PythonAPI/carla/agents/navigation/basic_agent.py index 093749d5a..44e6d0351 100644 --- a/PythonAPI/carla/agents/navigation/basic_agent.py +++ b/PythonAPI/carla/agents/navigation/basic_agent.py @@ -345,12 +345,14 @@ class BasicAgent(object): return None return Polygon(route_bb) - + if self._ignore_vehicles: return (False, None, -1) - if not vehicle_list: + if vehicle_list is None: vehicle_list = self._world.get_actors().filter("*vehicle*") + if len(vehicle_list) == 0: + return (False, None, -1) if not max_distance: max_distance = self._base_vehicle_threshold diff --git a/PythonAPI/carla/source/libcarla/Actor.cpp b/PythonAPI/carla/source/libcarla/Actor.cpp index 9686bb735..dda9d58a4 100644 --- a/PythonAPI/carla/source/libcarla/Actor.cpp +++ b/PythonAPI/carla/source/libcarla/Actor.cpp @@ -115,6 +115,12 @@ void export_actor() { .def("get_acceleration", &cc::Actor::GetAcceleration) .def("get_component_world_transform", &cc::Actor::GetComponentWorldTransform, (arg("component_name"))) .def("get_component_relative_transform", &cc::Actor::GetComponentRelativeTransform, (arg("component_name"))) + .def("get_bone_world_transforms", CALL_RETURNING_LIST(cc::Actor,GetBoneWorldTransforms)) + .def("get_bone_relative_transforms", CALL_RETURNING_LIST(cc::Actor,GetBoneRelativeTransforms)) + .def("get_component_names", CALL_RETURNING_LIST(cc::Actor,GetComponentNames)) + .def("get_bone_names", CALL_RETURNING_LIST(cc::Actor,GetBoneNames)) + .def("get_socket_world_transforms", CALL_RETURNING_LIST(cc::Actor,GetSocketWorldTransforms)) + .def("get_socket_relative_transforms", CALL_RETURNING_LIST(cc::Actor,GetSocketRelativeTransforms)) .def("set_location", &cc::Actor::SetLocation, (arg("location"))) .def("set_transform", &cc::Actor::SetTransform, (arg("transform"))) .def("set_target_velocity", &cc::Actor::SetTargetVelocity, (arg("velocity"))) diff --git a/PythonAPI/carla/source/libcarla/Commands.cpp b/PythonAPI/carla/source/libcarla/Commands.cpp index 7fd5166da..2e33c628c 100644 --- a/PythonAPI/carla/source/libcarla/Commands.cpp +++ b/PythonAPI/carla/source/libcarla/Commands.cpp @@ -82,9 +82,15 @@ void export_commands() { "__init__", &command_impl::CustomSpawnActorInit, (arg("blueprint"), arg("transform"), arg("parent"))) + .def( + "__init__", + &command_impl::CustomSpawnActorInit, + (arg("blueprint"), arg("transform"), arg("parent"), arg("attachment_type"), arg("socket_name"))) .def(init()) .def_readwrite("transform", &cr::Command::SpawnActor::transform) .def_readwrite("parent_id", &cr::Command::SpawnActor::parent) + .def_readwrite("attachment_type", &cr::Command::SpawnActor::attachment_type) + .def_readwrite("socket_name", &cr::Command::SpawnActor::socket_name) .def("then", &command_impl::Then, (arg("command"))) ; diff --git a/PythonAPI/carla/source/libcarla/World.cpp b/PythonAPI/carla/source/libcarla/World.cpp index 6f07518ba..0c59ebf32 100644 --- a/PythonAPI/carla/source/libcarla/World.cpp +++ b/PythonAPI/carla/source/libcarla/World.cpp @@ -11,6 +11,8 @@ #include #include +#include + #include namespace carla { @@ -293,15 +295,17 @@ void export_world() { const cc::ActorBlueprint &blueprint, \ const cg::Transform &transform, \ cc::Actor *parent, \ - cr::AttachmentType attachment_type) { \ + cr::AttachmentType attachment_type, \ + const std::string& bone) { \ carla::PythonUtil::ReleaseGIL unlock; \ - return self.fn(blueprint, transform, parent, attachment_type); \ + return self.fn(blueprint, transform, parent, attachment_type, bone); \ }, \ ( \ arg("blueprint"), \ arg("transform"), \ arg("attach_to")=carla::SharedPtr(), \ - arg("attachment_type")=cr::AttachmentType::Rigid) + arg("attachment_type")=cr::AttachmentType::Rigid, \ + arg("bone")=std::string()) class_("World", no_init) .add_property("id", &cc::World::GetId) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.cpp index 5d2417ab1..2e4951021 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.cpp @@ -105,7 +105,7 @@ bool UCarlaEpisode::LoadNewEpisode(const FString &MapString, bool ResetSettings) UGameplayStatics::OpenLevel(GetWorld(), *FinalPath, true); if (ResetSettings) ApplySettings(FEpisodeSettings{}); - + // send 'LOAD_MAP' command to all secondary servers (if any) if (bIsPrimaryServer) { @@ -114,7 +114,7 @@ bool UCarlaEpisode::LoadNewEpisode(const FString &MapString, bool ResetSettings) { FCarlaEngine *CarlaEngine = GameInstance->GetCarlaEngine(); auto SecondaryServer = CarlaEngine->GetSecondaryServer(); - if (SecondaryServer->HasClientsConnected()) + if (SecondaryServer->HasClientsConnected()) { SecondaryServer->GetCommander().SendLoadMap(std::string(TCHAR_TO_UTF8(*FinalPath))); } @@ -294,11 +294,12 @@ carla::rpc::Actor UCarlaEpisode::SerializeActor(AActor* Actor) const void UCarlaEpisode::AttachActors( AActor *Child, AActor *Parent, - EAttachmentType InAttachmentType) + EAttachmentType InAttachmentType, + const FString& SocketName) { Child->AddActorWorldOffset(FVector(CurrentMapOrigin)); - UActorAttacher::AttachActors(Child, Parent, InAttachmentType); + UActorAttacher::AttachActors(Child, Parent, InAttachmentType, SocketName); if (bIsPrimaryServer) { diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h index 14d078811..d1b820fea 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h @@ -245,7 +245,8 @@ public: void AttachActors( AActor *Child, AActor *Parent, - EAttachmentType InAttachmentType = EAttachmentType::Rigid); + EAttachmentType InAttachmentType = EAttachmentType::Rigid, + const FString& SocketName = ""); /// @copydoc FActorDispatcher::DestroyActor(AActor*) UFUNCTION(BlueprintCallable) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp index af6cbc658..7d06f0f81 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp @@ -9,6 +9,11 @@ #include "Carla/Server/CarlaServerResponse.h" #include "Carla/Traffic/TrafficLightGroup.h" #include "EngineUtils.h" +#include "Components/SkeletalMeshComponent.h" +#include "Components/SkinnedMeshComponent.h" +#include "Components/SceneComponent.h" +#include "Engine/SkeletalMesh.h" +#include "Engine/SkeletalMeshSocket.h" #include "Carla/OpenDrive/OpenDrive.h" #include "Carla/Util/DebugShapeDrawer.h" @@ -706,7 +711,8 @@ void FCarlaServer::FPimpl::BindActions() cr::ActorDescription Description, const cr::Transform &Transform, cr::ActorId ParentId, - cr::AttachmentType InAttachmentType) -> R + cr::AttachmentType InAttachmentType, + const std::string& socket_name) -> R { REQUIRE_CARLA_EPISODE(); @@ -760,7 +766,8 @@ void FCarlaServer::FPimpl::BindActions() Episode->AttachActors( CarlaActor->GetActor(), ParentCarlaActor->GetActor(), - static_cast(InAttachmentType)); + static_cast(InAttachmentType), + FString(socket_name.c_str())); } else { @@ -1292,7 +1299,7 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_ TArray Components; CarlaActor->GetActor()->GetComponents(Components); - USceneComponent* Component; + USceneComponent* Component = nullptr; for(auto Cmp : Components) { if(USceneComponent* SCMP = Cast(Cmp)) @@ -1336,7 +1343,7 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_ TArray Components; CarlaActor->GetActor()->GetComponents(Components); - USceneComponent* Component; + USceneComponent* Component = nullptr; for(auto Cmp : Components) { if(USceneComponent* SCMP = Cast(Cmp)) @@ -1362,6 +1369,217 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_ } }; + BIND_SYNC(get_actor_bone_world_transforms) << [this]( + cr::ActorId ActorId) -> R> + { + REQUIRE_CARLA_EPISODE(); + FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId); + if (!CarlaActor) + { + return RespondError( + "get_actor_bone_world_transform", + ECarlaServerResponse::ActorNotFound, + " Actor Id: " + FString::FromInt(ActorId)); + } + else + { + TArray BoneWorldTransforms; + TArray SkinnedMeshComponents; + CarlaActor->GetActor()->GetComponents(SkinnedMeshComponents); + if(!SkinnedMeshComponents[0]) + { + return RespondError( + "get_actor_bone_relative_transforms", + ECarlaServerResponse::ComponentNotFound, + " Component Name: SkinnedMeshComponent "); + } + else + { + for(USkinnedMeshComponent* SkinnedMeshComponent : SkinnedMeshComponents) + { + const int32 NumBones = SkinnedMeshComponent->GetNumBones(); + for (int32 BoneIndex = 0; BoneIndex < NumBones; ++BoneIndex) + { + FTransform WorldTransform = SkinnedMeshComponent->GetComponentTransform(); + FTransform BoneTransform = SkinnedMeshComponent->GetBoneTransform(BoneIndex, WorldTransform); + BoneWorldTransforms.Add(BoneTransform); + } + } + return MakeVectorFromTArray(BoneWorldTransforms); + } + } + }; + + BIND_SYNC(get_actor_bone_relative_transforms) << [this]( + cr::ActorId ActorId) -> R> + { + REQUIRE_CARLA_EPISODE(); + FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId); + if (!CarlaActor) + { + return RespondError( + "get_actor_bone_relative_transform", + ECarlaServerResponse::ActorNotFound, + " Actor Id: " + FString::FromInt(ActorId)); + } + else + { + TArray BoneRelativeTransforms; + TArray SkinnedMeshComponents; + CarlaActor->GetActor()->GetComponents(SkinnedMeshComponents); + if(!SkinnedMeshComponents[0]) + { + return RespondError( + "get_actor_bone_relative_transforms", + ECarlaServerResponse::ComponentNotFound, + " Component Name: SkinnedMeshComponent "); + } + else + { + for(USkinnedMeshComponent* SkinnedMeshComponent : SkinnedMeshComponents) + { + const int32 NumBones = SkinnedMeshComponent->GetNumBones(); + for (int32 BoneIndex = 0; BoneIndex < NumBones; ++BoneIndex) + { + FTransform BoneTransform = SkinnedMeshComponent->GetBoneTransform(BoneIndex, FTransform::Identity); + BoneRelativeTransforms.Add(BoneTransform); + } + } + return MakeVectorFromTArray(BoneRelativeTransforms); + } + } + }; + + BIND_SYNC(get_actor_component_names) << [this]( + cr::ActorId ActorId) -> R> + { + REQUIRE_CARLA_EPISODE(); + FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId); + if (!CarlaActor) + { + return RespondError( + "get_actor_component_names", + ECarlaServerResponse::ActorNotFound, + " Actor Id: " + FString::FromInt(ActorId)); + } + else + { + TArray Components; + CarlaActor->GetActor()->GetComponents(Components); + std::vector ComponentNames; + for(auto Cmp : Components) + { + FString ComponentName = Cmp->GetName(); + ComponentNames.push_back(TCHAR_TO_UTF8(*ComponentName)); + } + return ComponentNames; + } + }; + + BIND_SYNC(get_actor_bone_names) << [this]( + cr::ActorId ActorId) -> R> + { + REQUIRE_CARLA_EPISODE(); + FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId); + if (!CarlaActor) + { + return RespondError( + "get_actor_component_relative_transform", + ECarlaServerResponse::ActorNotFound, + " Actor Id: " + FString::FromInt(ActorId)); + } + else + { + USkinnedMeshComponent* SkinnedMeshComponent = CarlaActor->GetActor()->FindComponentByClass(); + if(!SkinnedMeshComponent) + { + return RespondError( + "get_actor_bone_relative_transforms", + ECarlaServerResponse::ComponentNotFound, + " Component Name: SkinnedMeshComponent "); + } + else + { + TArray BoneNames; + SkinnedMeshComponent->GetBoneNames(BoneNames); + TArray StringBoneNames; + for (const FName& Name : BoneNames) + { + FString FBoneName = Name.ToString(); + std::string StringBoneName = TCHAR_TO_UTF8(*FBoneName); + StringBoneNames.Add(StringBoneName); + } + return MakeVectorFromTArray(StringBoneNames); + } + } + }; + + BIND_SYNC(get_actor_socket_world_transforms) << [this]( + cr::ActorId ActorId) -> R> + { + REQUIRE_CARLA_EPISODE(); + FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId); + if (!CarlaActor) + { + return RespondError( + "get_actor_component_relative_transform", + ECarlaServerResponse::ActorNotFound, + " Actor Id: " + FString::FromInt(ActorId)); + } + else + { + TArray SocketWorldTransforms; + TArray Components; + CarlaActor->GetActor()->GetComponents(Components); + for(UActorComponent* ActorComponent : Components) + { + if(USceneComponent* SceneComponent = Cast(ActorComponent)) + { + const TArray& SocketNames = SceneComponent->GetAllSocketNames(); + for (const FName& SocketName : SocketNames) + { + FTransform SocketTransform = SceneComponent->GetSocketTransform(SocketName); + SocketWorldTransforms.Add(SocketTransform); + } + } + } + return MakeVectorFromTArray(SocketWorldTransforms); + } + }; + + BIND_SYNC(get_actor_socket_relative_transforms) << [this]( + cr::ActorId ActorId) -> R> + { + REQUIRE_CARLA_EPISODE(); + FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId); + if (!CarlaActor) + { + return RespondError( + "get_actor_component_relative_transform", + ECarlaServerResponse::ActorNotFound, + " Actor Id: " + FString::FromInt(ActorId)); + } + else + { + TArray SocketRelativeTransforms; + TArray Components; + CarlaActor->GetActor()->GetComponents(Components); + for(UActorComponent* ActorComponent : Components) + { + if(USceneComponent* SceneComponent = Cast(ActorComponent)) + { + const TArray& SocketNames = SceneComponent->GetAllSocketNames(); + for (const FName& SocketName : SocketNames) + { + FTransform SocketTransform = SceneComponent->GetSocketTransform(SocketName, ERelativeTransformSpace::RTS_Actor); + SocketRelativeTransforms.Add(SocketTransform); + } + } + } + return MakeVectorFromTArray(SocketRelativeTransforms); + } + }; + BIND_SYNC(get_physics_control) << [this]( cr::ActorId ActorId) -> R { @@ -2545,7 +2763,8 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_ c.description, c.transform, *c.parent, - cr::AttachmentType::Rigid) : + cr::AttachmentType::Rigid, + c.socket_name) : spawn_actor(c.description, c.transform); if (!result.HasError()) { diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/ActorAttacher.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/ActorAttacher.cpp index 56ca9185a..e0563522c 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/ActorAttacher.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/ActorAttacher.cpp @@ -96,7 +96,8 @@ static void UActorAttacher_AttachActorsWithSpringArmGhost( void UActorAttacher::AttachActors( AActor *Child, AActor *Parent, - const EAttachmentType AttachmentType) + const EAttachmentType AttachmentType, + const FString& SocketName) { check(Child != nullptr); check(Parent != nullptr); @@ -104,7 +105,7 @@ void UActorAttacher::AttachActors( switch (AttachmentType) { case EAttachmentType::Rigid: - Child->AttachToActor(Parent, FAttachmentTransformRules::KeepRelativeTransform); + Child->AttachToActor(Parent, FAttachmentTransformRules::KeepRelativeTransform, FName(*SocketName)); break; case EAttachmentType::SpringArm: UActorAttacher_AttachActorsWithSpringArm(Child, Parent); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/ActorAttacher.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/ActorAttacher.h index 4f6d5d1dd..e95c24ae7 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/ActorAttacher.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/ActorAttacher.h @@ -42,5 +42,5 @@ class CARLA_API UActorAttacher : public UBlueprintFunctionLibrary public: UFUNCTION(BlueprintCallable, Category="CARLA|Actor Attacher") - static void AttachActors(AActor *Child, AActor *Parent, EAttachmentType AttachmentType); + static void AttachActors(AActor *Child, AActor *Parent, EAttachmentType AttachmentType, const FString& SocketName = ""); }; diff --git a/Unreal/CarlaUE4/Plugins/CarlaTools/Content/OnroadMapGenerator/BP_OpenDriveToMap.uasset b/Unreal/CarlaUE4/Plugins/CarlaTools/Content/OnroadMapGenerator/BP_OpenDriveToMap.uasset index b73e2caa5..94bee4e50 100644 Binary files a/Unreal/CarlaUE4/Plugins/CarlaTools/Content/OnroadMapGenerator/BP_OpenDriveToMap.uasset and b/Unreal/CarlaUE4/Plugins/CarlaTools/Content/OnroadMapGenerator/BP_OpenDriveToMap.uasset differ diff --git a/Unreal/CarlaUE4/Plugins/CarlaTools/Content/OnroadMapGenerator/Blueprints/BP_BuildingGenerator.uasset b/Unreal/CarlaUE4/Plugins/CarlaTools/Content/OnroadMapGenerator/Blueprints/BP_BuildingGenerator.uasset index 165501747..0e6e56b65 100644 Binary files a/Unreal/CarlaUE4/Plugins/CarlaTools/Content/OnroadMapGenerator/Blueprints/BP_BuildingGenerator.uasset and b/Unreal/CarlaUE4/Plugins/CarlaTools/Content/OnroadMapGenerator/Blueprints/BP_BuildingGenerator.uasset differ diff --git a/Unreal/CarlaUE4/Plugins/CarlaTools/Content/OnroadMapGenerator/MapPreview/W_MapPreview.uasset b/Unreal/CarlaUE4/Plugins/CarlaTools/Content/OnroadMapGenerator/MapPreview/W_MapPreview.uasset index 3014c4eed..d978ae881 100644 Binary files a/Unreal/CarlaUE4/Plugins/CarlaTools/Content/OnroadMapGenerator/MapPreview/W_MapPreview.uasset and b/Unreal/CarlaUE4/Plugins/CarlaTools/Content/OnroadMapGenerator/MapPreview/W_MapPreview.uasset differ diff --git a/Unreal/CarlaUE4/Plugins/CarlaTools/Content/OnroadMapGenerator/UW_OnRoadMainWidget.uasset b/Unreal/CarlaUE4/Plugins/CarlaTools/Content/OnroadMapGenerator/UW_OnRoadMainWidget.uasset index d1c30094b..3ca4126ad 100644 Binary files a/Unreal/CarlaUE4/Plugins/CarlaTools/Content/OnroadMapGenerator/UW_OnRoadMainWidget.uasset and b/Unreal/CarlaUE4/Plugins/CarlaTools/Content/OnroadMapGenerator/UW_OnRoadMainWidget.uasset differ diff --git a/Unreal/CarlaUE4/Plugins/CarlaTools/Source/CarlaTools/Private/OpenDriveToMap.cpp b/Unreal/CarlaUE4/Plugins/CarlaTools/Source/CarlaTools/Private/OpenDriveToMap.cpp index 8ee027793..a3049125b 100644 --- a/Unreal/CarlaUE4/Plugins/CarlaTools/Source/CarlaTools/Private/OpenDriveToMap.cpp +++ b/Unreal/CarlaUE4/Plugins/CarlaTools/Source/CarlaTools/Private/OpenDriveToMap.cpp @@ -154,16 +154,32 @@ void UOpenDriveToMap::CreateMap() UE_LOG(LogCarlaToolsMapGenerator, Error, TEXT("Map Name Is Empty") ); return; } - if ( !IsValid(FileDownloader) ) + + if( !Url.IsEmpty() ) { + if ( !IsValid(FileDownloader) ) + { + FileDownloader = NewObject(); + } + + FileDownloader->ResultFileName = MapName; + FileDownloader->Url = Url; + + FileDownloader->DownloadDelegate.BindUObject( this, &UOpenDriveToMap::ConvertOSMInOpenDrive ); + FileDownloader->StartDownload(); + } + else if(LocalFilePath.EndsWith(".xodr")) { - FileDownloader = NewObject(); + ImportXODR(); + } + else if(LocalFilePath.EndsWith(".osm")) + { + ImportOSM(); + } + else + { + UE_LOG(LogCarlaToolsMapGenerator, Error, TEXT("URL and Local FilePath are Empty. URL: %s Local FilePath: %s"), *Url, *LocalFilePath ); } - FileDownloader->ResultFileName = MapName; - FileDownloader->Url = Url; - - FileDownloader->DownloadDelegate.BindUObject( this, &UOpenDriveToMap::ConvertOSMInOpenDrive ); - FileDownloader->StartDownload(); } void UOpenDriveToMap::CreateTerrain( const int MeshGridSize, const float MeshGridSectionSize) @@ -490,7 +506,7 @@ void UOpenDriveToMap::GenerateAll(const boost::optional& Param { GenerateRoadMesh(ParamCarlaMap, MinLocation, MaxLocation); GenerateLaneMarks(ParamCarlaMap, MinLocation, MaxLocation); - //GenerateSpawnPoints(ParamCarlaMap); + GenerateSpawnPoints(ParamCarlaMap, MinLocation, MaxLocation); CreateTerrain(12800, 256); GenerateTreePositions(ParamCarlaMap, MinLocation, MaxLocation); GenerationFinished(MinLocation, MaxLocation); @@ -714,10 +730,14 @@ void UOpenDriveToMap::GenerateSpawnPoints( const boost::optionalComputeTransform(Wp); - AVehicleSpawnPoint *Spawner = UEditorLevelLibrary::GetEditorWorld()->SpawnActor(); - Spawner->SetActorRotation(Trans.GetRotation()); - Spawner->SetActorLocation(Trans.GetTranslation() + FVector(0.f, 0.f, SpawnersHeight)); - ActorsToMove.Add(Spawner); + if( Trans.GetLocation().X >= MinLocation.X && Trans.GetLocation().Y >= MinLocation.Y && + Trans.GetLocation().X <= MaxLocation.X && Trans.GetLocation().Y <= MaxLocation.Y) + { + AVehicleSpawnPoint *Spawner = UEditorLevelLibrary::GetEditorWorld()->SpawnActor(); + Spawner->SetActorRotation(Trans.GetRotation()); + Spawner->SetActorLocation(Trans.GetTranslation() + FVector(0.f, 0.f, SpawnersHeight)); + ActorsToMove.Add(Spawner); + } } } @@ -878,6 +898,41 @@ bool UOpenDriveToMap::IsInRoad( return false; } +void UOpenDriveToMap::ImportXODR(){ + IPlatformFile& FileManager = FPlatformFileManager::Get().GetPlatformFile(); + FString MyFileDestination = FPaths::ProjectContentDir() + "CustomMaps/" + MapName + "/OpenDrive/" + MapName + ".xodr"; + + if(FileManager.CopyFile( *MyFileDestination, *LocalFilePath, + EPlatformFileRead::None, + EPlatformFileWrite::None)) + { + UE_LOG(LogCarlaToolsMapGenerator, Verbose, TEXT("FilePaths: File Copied!")); + FilePath = MyFileDestination; + LoadMap(); + } + else + { + UE_LOG(LogCarlaToolsMapGenerator, Error, TEXT("FilePaths local xodr file not copied: File not Copied!")); + } +} + +void UOpenDriveToMap::ImportOSM(){ + IPlatformFile& FileManager = FPlatformFileManager::Get().GetPlatformFile(); + FString MyFileDestination = FPaths::ProjectContentDir() + "CustomMaps/" + MapName + "/OpenDrive/" + MapName + ".osm"; + + if(FileManager.CopyFile( *MyFileDestination, *LocalFilePath, + EPlatformFileRead::None, + EPlatformFileWrite::None)) + { + UE_LOG(LogCarlaToolsMapGenerator, Verbose, TEXT("FilePaths: File Copied!")); + ConvertOSMInOpenDrive(); + } + else + { + UE_LOG(LogCarlaToolsMapGenerator, Error, TEXT("FilePaths local osm file not copied: File not Copied!")); + } +} + void UOpenDriveToMap::MoveActorsToSubLevels(TArray ActorsToMove) { AActor* QueryActor = UGameplayStatics::GetActorOfClass( diff --git a/Unreal/CarlaUE4/Plugins/CarlaTools/Source/CarlaTools/Public/OpenDriveToMap.h b/Unreal/CarlaUE4/Plugins/CarlaTools/Source/CarlaTools/Public/OpenDriveToMap.h index 2002c8275..115b456bb 100644 --- a/Unreal/CarlaUE4/Plugins/CarlaTools/Source/CarlaTools/Public/OpenDriveToMap.h +++ b/Unreal/CarlaUE4/Plugins/CarlaTools/Source/CarlaTools/Public/OpenDriveToMap.h @@ -91,6 +91,9 @@ public: UPROPERTY( EditAnywhere, BlueprintReadWrite, Category="Settings" ) FString Url; + UPROPERTY( EditAnywhere, BlueprintReadWrite, Category="Settings" ) + FString LocalFilePath; + UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Settings") FVector2D OriginGeoCoordinates; @@ -213,6 +216,9 @@ private: void InitTextureData(); + void ImportXODR(); + void ImportOSM(); + UPROPERTY() UCustomFileDownloader* FileDownloader; UPROPERTY() diff --git a/Util/BuildTools/BuildCarlaUE4.bat b/Util/BuildTools/BuildCarlaUE4.bat index bae39a3a1..cb61ed5d2 100644 --- a/Util/BuildTools/BuildCarlaUE4.bat +++ b/Util/BuildTools/BuildCarlaUE4.bat @@ -155,10 +155,10 @@ if exist %OMNIVERSE_PLUGIN_FOLDER% ( ) if %USE_CARSIM% == true ( - py -3 %ROOT_PATH%Util/BuildTools/enable_carsim_to_uproject.py -f="%ROOT_PATH%Unreal/CarlaUE4/CarlaUE4.uproject" -e + python %ROOT_PATH%Util/BuildTools/enable_carsim_to_uproject.py -f="%ROOT_PATH%Unreal/CarlaUE4/CarlaUE4.uproject" -e set CARSIM_STATE="CarSim ON" ) else ( - py -3 %ROOT_PATH%Util/BuildTools/enable_carsim_to_uproject.py -f="%ROOT_PATH%Unreal/CarlaUE4/CarlaUE4.uproject" + python %ROOT_PATH%Util/BuildTools/enable_carsim_to_uproject.py -f="%ROOT_PATH%Unreal/CarlaUE4/CarlaUE4.uproject" set CARSIM_STATE="CarSim OFF" ) if %USE_CHRONO% == true ( diff --git a/Util/BuildTools/BuildPythonAPI.bat b/Util/BuildTools/BuildPythonAPI.bat index cc8d92504..9812c8220 100644 --- a/Util/BuildTools/BuildPythonAPI.bat +++ b/Util/BuildTools/BuildPythonAPI.bat @@ -109,7 +109,7 @@ rem Build for Python 3 rem if %BUILD_FOR_PYTHON3%==true ( echo Building Python API for Python 3. - py -3 setup.py bdist_egg bdist_wheel + python setup.py bdist_egg bdist_wheel if %errorlevel% neq 0 goto error_build_wheel ) diff --git a/Util/BuildTools/Package.bat b/Util/BuildTools/Package.bat index 6be833077..82f03da84 100644 --- a/Util/BuildTools/Package.bat +++ b/Util/BuildTools/Package.bat @@ -119,10 +119,10 @@ rem ============================================================================ if %DO_PACKAGE%==true ( if %USE_CARSIM% == true ( - py -3 %ROOT_PATH%Util/BuildTools/enable_carsim_to_uproject.py -f="%ROOT_PATH%Unreal/CarlaUE4/CarlaUE4.uproject" -e + python %ROOT_PATH%Util/BuildTools/enable_carsim_to_uproject.py -f="%ROOT_PATH%Unreal/CarlaUE4/CarlaUE4.uproject" -e echo CarSim ON > "%ROOT_PATH%Unreal/CarlaUE4/Config/CarSimConfig.ini" ) else ( - py -3 %ROOT_PATH%Util/BuildTools/enable_carsim_to_uproject.py -f="%ROOT_PATH%Unreal/CarlaUE4/CarlaUE4.uproject" + python %ROOT_PATH%Util/BuildTools/enable_carsim_to_uproject.py -f="%ROOT_PATH%Unreal/CarlaUE4/CarlaUE4.uproject" echo CarSim OFF > "%ROOT_PATH%Unreal/CarlaUE4/Config/CarSimConfig.ini" ) diff --git a/Util/BuildTools/Setup.sh b/Util/BuildTools/Setup.sh index 0a46ae555..81a416d07 100755 --- a/Util/BuildTools/Setup.sh +++ b/Util/BuildTools/Setup.sh @@ -92,15 +92,30 @@ for PY_VERSION in ${PY_VERSION_LIST[@]} ; do BOOST_PACKAGE_BASENAME=boost_${BOOST_VERSION//./_} log "Retrieving boost." + + start=$(date +%s) wget "https://archives.boost.io/release/${BOOST_VERSION}/source/${BOOST_PACKAGE_BASENAME}.tar.gz" || true + end=$(date +%s) + echo "Elapsed Time downloading from boost webpage: $(($end-$start)) seconds" + # try to use the backup boost we have in Jenkins if [ ! -f "${BOOST_PACKAGE_BASENAME}.tar.gz" ] || [[ $(sha256sum "${BOOST_PACKAGE_BASENAME}.tar.gz") != "${BOOST_SHA256SUM}" ]] ; then log "Using boost backup" + + start=$(date +%s) wget "https://carla-releases.s3.us-east-005.backblazeb2.com/Backup/${BOOST_PACKAGE_BASENAME}.tar.gz" || true + end=$(date +%s) + echo "Elapsed Time downloading from boost carla backup in backblaze: $(($end-$start)) seconds" + fi log "Extracting boost for Python ${PY_VERSION}." + + start=$(date +%s) tar -xzf ${BOOST_PACKAGE_BASENAME}.tar.gz + end=$(date +%s) + echo "Elapsed Time Extracting boost for Python: $(($end-$start)) seconds" + mkdir -p ${BOOST_BASENAME}-install/include mv ${BOOST_PACKAGE_BASENAME} ${BOOST_BASENAME}-source @@ -166,8 +181,13 @@ else log "Retrieving rpclib." + start_download_time=$(date +%s) + git clone -b ${RPCLIB_PATCH} https://github.com/carla-simulator/rpclib.git ${RPCLIB_BASENAME}-source + end_download_time=$(date +%s) + + echo "Elapsed Time downloading rpclib: $(($end_download_time-$start_download_time)) seconds" log "Building rpclib with libc++." # rpclib does not use any cmake 3.9 feature. @@ -234,8 +254,13 @@ else log "Retrieving Google Test." + start_download_time=$(date +%s) + git clone --depth=1 -b release-${GTEST_VERSION} https://github.com/google/googletest.git ${GTEST_BASENAME}-source + end_download_time=$(date +%s) + echo "Elapsed Time downloading rpclib: $(($end-$start)) seconds" + log "Building Google Test with libc++." mkdir -p ${GTEST_BASENAME}-libcxx-build @@ -296,12 +321,15 @@ else log "Retrieving Recast & Detour" - git clone https://github.com/carla-simulator/recastnavigation.git ${RECAST_BASENAME}-source + start=$(date +%s) + + git clone --depth 1 -b carla https://github.com/carla-simulator/recastnavigation.git ${RECAST_BASENAME}-source + + end=$(date +%s) + echo "Elapsed Time downloading: $(($end-$start)) seconds" pushd ${RECAST_BASENAME}-source >/dev/null - git checkout carla - popd >/dev/null log "Building Recast & Detour with libc++." @@ -351,10 +379,18 @@ if [[ -d ${LIBPNG_INSTALL} ]] ; then log "Libpng already installed." else log "Retrieving libpng." - wget ${LIBPNG_REPO} + start=$(date +%s) + wget ${LIBPNG_REPO} + end=$(date +%s) + echo "Elapsed Time downloading libpng: $(($end-$start)) seconds" + + start=$(date +%s) log "Extracting libpng." tar -xf libpng-${LIBPNG_VERSION}.tar.xz + end=$(date +%s) + echo "Elapsed Time Extracting libpng: $(($end-$start)) seconds" + mv ${LIBPNG_BASENAME} ${LIBPNG_BASENAME}-source pushd ${LIBPNG_BASENAME}-source >/dev/null @@ -388,16 +424,26 @@ if [[ -d ${XERCESC_INSTALL_DIR} && -d ${XERCESC_INSTALL_SERVER_DIR} ]] ; then log "Xerces-c already installed." else log "Retrieving xerces-c." + start=$(date +%s) wget ${XERCESC_REPO} - + end=$(date +%s) + echo "Elapsed Time downloading from xerces repo: $(($end-$start)) seconds" # try to use the backup boost we have in Jenkins if [[ ! -f "${XERCESC_BASENAME}.tar.gz" ]] ; then log "Using xerces backup" + start=$(date +%s) wget "https://carla-releases.s3.us-east-005.backblazeb2.com/Backup/${XERCESC_BASENAME}.tar.gz" || true + end=$(date +%s) + echo "Elapsed Time downloading from xerces backup: $(($end-$start)) seconds" fi log "Extracting xerces-c." + + start=$(date +%s) tar -xzf ${XERCESC_BASENAME}.tar.gz + end=$(date +%s) + echo "Elapsed Time Extracting xerces-c: $(($end-$start)) seconds" + mv ${XERCESC_BASENAME} ${XERCESC_SRC_DIR} mkdir -p ${XERCESC_INSTALL_DIR} mkdir -p ${XERCESC_SRC_DIR}/build @@ -461,10 +507,18 @@ if [[ -d ${EIGEN_INSTALL_DIR} ]] ; then log "Eigen already installed." else log "Retrieving Eigen." + + start=$(date +%s) wget ${EIGEN_REPO} + end=$(date +%s) + echo "Elapsed Time downloading from eigen repo: $(($end-$start)) seconds" log "Extracting Eigen." + start=$(date +%s) tar -xzf ${EIGEN_BASENAME}.tar.gz + end=$(date +%s) + echo "Elapsed Time Extracting EIGEN: $(($end-$start)) seconds" + mv ${EIGEN_BASENAME} ${EIGEN_SRC_DIR} mkdir -p ${EIGEN_INCLUDE}/unsupported mv ${EIGEN_SRC_DIR}/Eigen ${EIGEN_INCLUDE} @@ -496,10 +550,19 @@ if ${USE_CHRONO} ; then log "Eigen already installed." else log "Retrieving Eigen." + + start=$(date +%s) wget ${EIGEN_REPO} + end=$(date +%s) + echo "Elapsed Time: $(($end-$start)) seconds" log "Extracting Eigen." + + start=$(date +%s) tar -xzf ${EIGEN_BASENAME}.tar.gz + end=$(date +%s) + echo "Elapsed Time Extracting for Eigen: $(($end-$start)) seconds" + mv ${EIGEN_BASENAME} ${EIGEN_SRC_DIR} mkdir -p ${EIGEN_INCLUDE}/unsupported mv ${EIGEN_SRC_DIR}/Eigen ${EIGEN_INCLUDE} @@ -527,7 +590,10 @@ if ${USE_CHRONO} ; then log "chrono library already installed." else log "Retrieving chrono library." + start=$(date +%s) git clone --depth 1 --branch ${CHRONO_TAG} ${CHRONO_REPO} ${CHRONO_SRC_DIR} + end=$(date +%s) + echo "Elapsed Time dowloading chrono: $(($end-$start)) seconds" mkdir -p ${CHRONO_SRC_DIR}/build @@ -574,10 +640,19 @@ if [[ -d ${SQLITE_INSTALL_DIR} ]] ; then log "Sqlite already installed." else log "Retrieving Sqlite3" + + start=$(date +%s) wget ${SQLITE_REPO} + end=$(date +%s) + echo "Elapsed Time: $(($end-$start)) seconds" log "Extracting Sqlite3" + + start=$(date +%s) tar -xzf ${SQLITE_TAR} + end=$(date +%s) + echo "Elapsed Time Extracting for SQlite: $(($end-$start)) seconds" + mv ${SQLITE_VERSION} ${SQLITE_SOURCE_DIR} mkdir ${SQLITE_INSTALL_DIR} @@ -621,10 +696,18 @@ if [[ -d ${PROJ_INSTALL_DIR} && -d ${PROJ_INSTALL_SERVER_DIR_FULL} ]] ; then log "PROJ already installed." else log "Retrieving PROJ" + + start=$(date +%s) wget ${PROJ_REPO} + end=$(date +%s) + echo "Elapsed Time: $(($end-$start)) seconds" log "Extracting PROJ" + start=$(date +%s) tar -xzf ${PROJ_TAR} + end=$(date +%s) + echo "Elapsed Time Extracting for PROJ: $(($end-$start)) seconds" + mv ${PROJ_VERSION} ${PROJ_SRC_DIR} mkdir -p ${PROJ_SRC_DIR}/build @@ -692,10 +775,18 @@ if [[ -d ${PATCHELF_INSTALL_DIR} ]] ; then log "Patchelf already installed." else log "Retrieving patchelf" + + start=$(date +%s) wget ${PATCHELF_REPO} + end=$(date +%s) + echo "Elapsed Time: $(($end-$start)) seconds" log "Extracting patchelf" + start=$(date +%s) tar -xzf ${PATCHELF_TAR} + end=$(date +%s) + echo "Elapsed Time Extracting patchelf: $(($end-$start)) seconds" + mv patchelf-${PATCHELF_VERSION} ${PATCHELF_SOURCE_DIR} mkdir ${PATCHELF_INSTALL_DIR} @@ -730,7 +821,12 @@ if ${USE_PYTORCH} ; then LIBTORCH_ZIPFILE=libtorch-shared-with-deps-1.11.0+cu113.zip LIBTORCH_REPO=https://download.pytorch.org/libtorch/cu113/libtorch-shared-with-deps-1.11.0%2Bcu113.zip if [[ ! -d ${LIBTORCH_PATH} ]] ; then + + start=$(date +%s) wget ${LIBTORCH_REPO} + end=$(date +%s) + echo "Elapsed Time downloading LIBTORCH_REPO: $(($end-$start)) seconds" + unzip ${LIBTORCH_ZIPFILE} fi @@ -810,7 +906,10 @@ if ${USE_ROS2} ; then if [[ ! -d ${LIB_SOURCE} ]] ; then mkdir -p ${LIB_SOURCE} log "${LIB_REPO}" + start=$(date +%s) git clone --depth 1 --branch ${LIB_BRANCH} ${LIB_REPO} ${LIB_SOURCE} + end=$(date +%s) + echo "Elapsed Time dowloading fastdds extension: $(($end-$start)) seconds" mkdir -p ${LIB_SOURCE}/build fi }