From fda970b88191f401a32ea4305704562773b48b8b Mon Sep 17 00:00:00 2001 From: Andrew Patrikalakis Date: Sun, 10 Mar 2024 14:31:05 -0400 Subject: [PATCH 01/11] Allow GetVehiclePhysicsControl to succeed when physics is off --- .../Carla/Vehicle/CarlaWheeledVehicle.cpp | 58 ++++++++++++------- 1 file changed, 36 insertions(+), 22 deletions(-) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp index 8ba705acd5e..22a025444fc 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp @@ -459,17 +459,25 @@ FVehiclePhysicsControl ACarlaWheeledVehicle::GetVehiclePhysicsControl() const { FWheelPhysicsControl PhysicsWheel; - PxVehicleWheelData PWheelData = Vehicle4W->PVehicle->mWheelsSimData.getWheelData(i); - PhysicsWheel.DampingRate = Cm2ToM2(PWheelData.mDampingRate); - PhysicsWheel.MaxSteerAngle = FMath::RadiansToDegrees(PWheelData.mMaxSteer); - PhysicsWheel.Radius = PWheelData.mRadius; - PhysicsWheel.MaxBrakeTorque = Cm2ToM2(PWheelData.mMaxBrakeTorque); - PhysicsWheel.MaxHandBrakeTorque = Cm2ToM2(PWheelData.mMaxHandBrakeTorque); - - PxVehicleTireData PTireData = Vehicle4W->PVehicle->mWheelsSimData.getTireData(i); - PhysicsWheel.LatStiffMaxLoad = PTireData.mLatStiffX; - PhysicsWheel.LatStiffValue = PTireData.mLatStiffY; - PhysicsWheel.LongStiffValue = PTireData.mLongitudinalStiffnessPerUnitGravity; + if (bPhysicsEnabled) { + PxVehicleWheelData PWheelData = Vehicle4W->PVehicle->mWheelsSimData.getWheelData(i); + + PhysicsWheel.DampingRate = Cm2ToM2(PWheelData.mDampingRate); + PhysicsWheel.MaxSteerAngle = FMath::RadiansToDegrees(PWheelData.mMaxSteer); + PhysicsWheel.Radius = PWheelData.mRadius; + PhysicsWheel.MaxBrakeTorque = Cm2ToM2(PWheelData.mMaxBrakeTorque); + PhysicsWheel.MaxHandBrakeTorque = Cm2ToM2(PWheelData.mMaxHandBrakeTorque); + + PxVehicleTireData PTireData = Vehicle4W->PVehicle->mWheelsSimData.getTireData(i); + + PhysicsWheel.LatStiffMaxLoad = PTireData.mLatStiffX; + PhysicsWheel.LatStiffValue = PTireData.mLatStiffY; + PhysicsWheel.LongStiffValue = PTireData.mLongitudinalStiffnessPerUnitGravity; + } else { + if (i < LastPhysicsControl.Wheels.Num()) { + PhysicsWheel = LastPhysicsControl.Wheels[i]; + } + } PhysicsWheel.TireFriction = Vehicle4W->Wheels[i]->TireConfig->GetFrictionScale(); PhysicsWheel.Position = Vehicle4W->Wheels[i]->Location; @@ -537,17 +545,23 @@ FVehiclePhysicsControl ACarlaWheeledVehicle::GetVehiclePhysicsControl() const { FWheelPhysicsControl PhysicsWheel; - PxVehicleWheelData PWheelData = VehicleNW->PVehicle->mWheelsSimData.getWheelData(i); - PhysicsWheel.DampingRate = Cm2ToM2(PWheelData.mDampingRate); - PhysicsWheel.MaxSteerAngle = FMath::RadiansToDegrees(PWheelData.mMaxSteer); - PhysicsWheel.Radius = PWheelData.mRadius; - PhysicsWheel.MaxBrakeTorque = Cm2ToM2(PWheelData.mMaxBrakeTorque); - PhysicsWheel.MaxHandBrakeTorque = Cm2ToM2(PWheelData.mMaxHandBrakeTorque); - - PxVehicleTireData PTireData = VehicleNW->PVehicle->mWheelsSimData.getTireData(i); - PhysicsWheel.LatStiffMaxLoad = PTireData.mLatStiffX; - PhysicsWheel.LatStiffValue = PTireData.mLatStiffY; - PhysicsWheel.LongStiffValue = PTireData.mLongitudinalStiffnessPerUnitGravity; + if (bPhysicsEnabled) { + PxVehicleWheelData PWheelData = VehicleNW->PVehicle->mWheelsSimData.getWheelData(i); + PhysicsWheel.DampingRate = Cm2ToM2(PWheelData.mDampingRate); + PhysicsWheel.MaxSteerAngle = FMath::RadiansToDegrees(PWheelData.mMaxSteer); + PhysicsWheel.Radius = PWheelData.mRadius; + PhysicsWheel.MaxBrakeTorque = Cm2ToM2(PWheelData.mMaxBrakeTorque); + PhysicsWheel.MaxHandBrakeTorque = Cm2ToM2(PWheelData.mMaxHandBrakeTorque); + + PxVehicleTireData PTireData = VehicleNW->PVehicle->mWheelsSimData.getTireData(i); + PhysicsWheel.LatStiffMaxLoad = PTireData.mLatStiffX; + PhysicsWheel.LatStiffValue = PTireData.mLatStiffY; + PhysicsWheel.LongStiffValue = PTireData.mLongitudinalStiffnessPerUnitGravity; + } else { + if (i < LastPhysicsControl.Wheels.Num()) { + PhysicsWheel = LastPhysicsControl.Wheels[i]; + } + } PhysicsWheel.TireFriction = VehicleNW->Wheels[i]->TireConfig->GetFrictionScale(); PhysicsWheel.Position = VehicleNW->Wheels[i]->Location; From 3eb9a76263ff347002b6aa69f767e7778c486fc1 Mon Sep 17 00:00:00 2001 From: javiergrCS <139075626+javiergrCS@users.noreply.github.com> Date: Wed, 13 Mar 2024 23:02:00 +0100 Subject: [PATCH 02/11] Javiergr cs/get socket names (#7170) * Added new function to obtain the name of all actor sockets * Updating CHANGELOG.md * Simplifying code of get_actor_socket_names function --------- Co-authored-by: Blyron <53337103+Blyron@users.noreply.github.com> --- CHANGELOG.md | 1 + LibCarla/source/carla/client/Actor.cpp | 4 ++ LibCarla/source/carla/client/Actor.h | 2 + .../source/carla/client/detail/Client.cpp | 5 ++ LibCarla/source/carla/client/detail/Client.h | 3 ++ .../source/carla/client/detail/Simulator.h | 4 ++ PythonAPI/carla/source/libcarla/Actor.cpp | 3 +- .../Carla/Source/Carla/Server/CarlaServer.cpp | 49 ++++++++++++++++--- 8 files changed, 63 insertions(+), 8 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 001a458050c..c2f8e8152bf 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -8,6 +8,7 @@ * 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. + * Added function to get actor' sockets names * 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) * Added possibility to change gravity variable in imui sensor for the accelerometer diff --git a/LibCarla/source/carla/client/Actor.cpp b/LibCarla/source/carla/client/Actor.cpp index 0d2b7f962e3..497c99b0293 100644 --- a/LibCarla/source/carla/client/Actor.cpp +++ b/LibCarla/source/carla/client/Actor.cpp @@ -64,6 +64,10 @@ namespace client { return GetEpisode().Lock()->GetActorSocketRelativeTransforms(*this); } + std::vector Actor::GetSocketNames() const { + return GetEpisode().Lock()->GetActorSocketNames(*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 4afd48d4a9d..c84d59798af 100644 --- a/LibCarla/source/carla/client/Actor.h +++ b/LibCarla/source/carla/client/Actor.h @@ -76,6 +76,8 @@ namespace client { std::vector GetSocketRelativeTransforms() const; + std::vector GetSocketNames() const; + /// Teleport the actor to @a location. void SetLocation(const geom::Location &location); diff --git a/LibCarla/source/carla/client/detail/Client.cpp b/LibCarla/source/carla/client/detail/Client.cpp index b5e60293d99..b2715fcd9fc 100644 --- a/LibCarla/source/carla/client/detail/Client.cpp +++ b/LibCarla/source/carla/client/detail/Client.cpp @@ -456,6 +456,11 @@ namespace detail { return _pimpl->CallAndWait("get_actor_socket_relative_transforms", actor); } + std::vector Client::GetActorSocketNames(rpc::ActorId actor) { + using return_t = std::vector; + return _pimpl->CallAndWait("get_actor_socket_names", 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 a542163dd52..f776441827c 100644 --- a/LibCarla/source/carla/client/detail/Client.h +++ b/LibCarla/source/carla/client/detail/Client.h @@ -263,6 +263,9 @@ namespace detail { std::vector GetActorSocketRelativeTransforms( rpc::ActorId actor); + std::vector GetActorSocketNames( + rpc::ActorId actor); + void SetActorSimulatePhysics( rpc::ActorId actor, bool enabled); diff --git a/LibCarla/source/carla/client/detail/Simulator.h b/LibCarla/source/carla/client/detail/Simulator.h index 07b617b1c93..c6d529347ce 100644 --- a/LibCarla/source/carla/client/detail/Simulator.h +++ b/LibCarla/source/carla/client/detail/Simulator.h @@ -479,6 +479,10 @@ namespace detail { return _client.GetActorSocketRelativeTransforms(actor.GetId()); } + std::vector GetActorSocketNames(const Actor &actor) { + return _client.GetActorSocketNames(actor.GetId()); + } + void SetActorLocation(Actor &actor, const geom::Location &location) { _client.SetActorLocation(actor.GetId(), location); } diff --git a/PythonAPI/carla/source/libcarla/Actor.cpp b/PythonAPI/carla/source/libcarla/Actor.cpp index dda9d58a45c..3f9b4ef7e44 100644 --- a/PythonAPI/carla/source/libcarla/Actor.cpp +++ b/PythonAPI/carla/source/libcarla/Actor.cpp @@ -120,7 +120,8 @@ void export_actor() { .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("get_socket_relative_transforms", CALL_RETURNING_LIST(cc::Actor,GetSocketRelativeTransforms)) + .def("get_socket_names", CALL_RETURNING_LIST(cc::Actor,GetSocketNames)) .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/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp index a579771ae16..6d945ccf568 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp @@ -1402,7 +1402,7 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_ if (!CarlaActor) { return RespondError( - "get_actor_bone_world_transform", + "get_actor_bone_world_transforms", ECarlaServerResponse::ActorNotFound, " Actor Id: " + FString::FromInt(ActorId)); } @@ -1414,7 +1414,7 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_ if(!SkinnedMeshComponents[0]) { return RespondError( - "get_actor_bone_relative_transforms", + "get_actor_bone_world_transforms", ECarlaServerResponse::ComponentNotFound, " Component Name: SkinnedMeshComponent "); } @@ -1443,7 +1443,7 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_ if (!CarlaActor) { return RespondError( - "get_actor_bone_relative_transform", + "get_actor_bone_relative_transforms", ECarlaServerResponse::ActorNotFound, " Actor Id: " + FString::FromInt(ActorId)); } @@ -1509,7 +1509,7 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_ if (!CarlaActor) { return RespondError( - "get_actor_component_relative_transform", + "get_actor_bone_names", ECarlaServerResponse::ActorNotFound, " Actor Id: " + FString::FromInt(ActorId)); } @@ -1519,7 +1519,7 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_ if(!SkinnedMeshComponent) { return RespondError( - "get_actor_bone_relative_transforms", + "get_actor_bone_names", ECarlaServerResponse::ComponentNotFound, " Component Name: SkinnedMeshComponent "); } @@ -1547,7 +1547,7 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_ if (!CarlaActor) { return RespondError( - "get_actor_component_relative_transform", + "get_actor_socket_world_transforms", ECarlaServerResponse::ActorNotFound, " Actor Id: " + FString::FromInt(ActorId)); } @@ -1580,7 +1580,7 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_ if (!CarlaActor) { return RespondError( - "get_actor_component_relative_transform", + "get_actor_socket_relative_transforms", ECarlaServerResponse::ActorNotFound, " Actor Id: " + FString::FromInt(ActorId)); } @@ -1605,6 +1605,41 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_ } }; + BIND_SYNC(get_actor_socket_names) << [this]( + cr::ActorId ActorId) -> R> + { + REQUIRE_CARLA_EPISODE(); + FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId); + if (!CarlaActor) + { + return RespondError( + "get_actor_socket_names", + ECarlaServerResponse::ActorNotFound, + " Actor Id: " + FString::FromInt(ActorId)); + } + else + { + TArray SocketNames; + std::vector StringSocketNames; + TArray Components; + CarlaActor->GetActor()->GetComponents(Components); + for(UActorComponent* ActorComponent : Components) + { + if(USceneComponent* SceneComponent = Cast(ActorComponent)) + { + SocketNames = SceneComponent->GetAllSocketNames(); + for (const FName& Name : SocketNames) + { + FString FSocketName = Name.ToString(); + std::string StringSocketName = TCHAR_TO_UTF8(*FSocketName); + StringSocketNames.push_back(StringSocketName); + } + } + } + return StringSocketNames; + } + }; + BIND_SYNC(get_physics_control) << [this]( cr::ActorId ActorId) -> R { From 7c9233bb546a868e811306394205161c84f4ed16 Mon Sep 17 00:00:00 2001 From: Daraan Date: Mon, 18 Mar 2024 10:41:05 +0100 Subject: [PATCH 03/11] Fixing distro deprecation in setup.py and failing installation on pure Debian (#6802) * Fixed distro deprecation, failing on Debian * Updated CHANELOG.md for distro deprecation * Update setup.py Substituted double occurring list. --------- Co-authored-by: Daniel@copernicus --- CHANGELOG.md | 2 ++ PythonAPI/carla/setup.py | 9 +++++---- 2 files changed, 7 insertions(+), 4 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index c2f8e8152bf..7e721cba5aa 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -39,6 +39,8 @@ * Fixed bug causing the `FPixelReader::SavePixelsToDisk(PixelData, FilePath)` function to crash due to pixel array not set correctly. * Fixed segfaults in Python API due to incorrect GIL locking under Python 3.10. * Fixed the import script, where could use any other TilesInfo.txt if the destination folder has many + * Fixed PythonAPI not installing on Debian due to deprecated function of distro in setup.py. Less ambiguous error for other posix platforms. + ## CARLA 0.9.14 diff --git a/PythonAPI/carla/setup.py b/PythonAPI/carla/setup.py index 067e140a9c9..1e4b86b7b25 100755 --- a/PythonAPI/carla/setup.py +++ b/PythonAPI/carla/setup.py @@ -33,9 +33,10 @@ def walk(folder, file_filter='*'): if os.name == "posix": import distro - - linux_distro = distro.linux_distribution()[0] - if linux_distro.lower() in ["ubuntu", "debian", "deepin"]: + supported_dists = ["ubuntu", "debian", "deepin"] + + linux_distro = distro.id().lower() + if linux_distro in supported_dists: pwd = os.path.dirname(os.path.realpath(__file__)) pylib = "libboost_python%d%d.a" % (sys.version_info.major, sys.version_info.minor) @@ -101,7 +102,7 @@ def walk(folder, file_filter='*'): # extra_link_args += ['/usr/lib/gcc/x86_64-linux-gnu/7/libstdc++.a'] extra_link_args += ['-lstdc++'] else: - raise NotImplementedError + raise NotImplementedError(linux_distro + " not in supported posix platforms: " + str(supported_dists)) elif os.name == "nt": pwd = os.path.dirname(os.path.realpath(__file__)) pylib = 'libboost_python%d%d' % ( From c0409b937d1875405eeb3d7074ff5d21d70b9c95 Mon Sep 17 00:00:00 2001 From: xavisolesoft Date: Tue, 19 Mar 2024 10:25:44 +0000 Subject: [PATCH 04/11] ROS2: Force foonathan memory vendor lib to build even ROS2 is installed on the system --- Util/BuildTools/Setup.bat | 1 + Util/BuildTools/Setup.sh | 1 + 2 files changed, 2 insertions(+) diff --git a/Util/BuildTools/Setup.bat b/Util/BuildTools/Setup.bat index 99dd8bb82ff..5a496a96640 100644 --- a/Util/BuildTools/Setup.bat +++ b/Util/BuildTools/Setup.bat @@ -320,6 +320,7 @@ IF "%USE_ROS2%"=="true" ( -DCMAKE_INSTALL_PREFIX="%FASTDDS_INSTALL_DIR%" ^ -DBUILD_SHARED_LIBS=ON ^ -DCMAKE_CXX_FLAGS_RELEASE="-D_GLIBCXX_USE_CXX11_ABI=0" ^ + -DFOONATHAN_MEMORY_FORCE_VENDORED_BUILD=ON ^ .. ninja ninja install diff --git a/Util/BuildTools/Setup.sh b/Util/BuildTools/Setup.sh index 81a416d07cf..21e8204fbd4 100755 --- a/Util/BuildTools/Setup.sh +++ b/Util/BuildTools/Setup.sh @@ -926,6 +926,7 @@ if ${USE_ROS2} ; then -DCMAKE_INSTALL_PREFIX="${FASTDDS_INSTALL_DIR}" \ -DBUILD_SHARED_LIBS=ON \ -DCMAKE_CXX_FLAGS_RELEASE="-D_GLIBCXX_USE_CXX11_ABI=0" \ + -DFOONATHAN_MEMORY_FORCE_VENDORED_BUILD=ON \ .. ninja ninja install From 3fdd2c2e52e41f042eaafaa1ee3953c416d6c0b1 Mon Sep 17 00:00:00 2001 From: xavisolesoft Date: Tue, 19 Mar 2024 12:14:48 +0000 Subject: [PATCH 05/11] Add change log. --- CHANGELOG.md | 1 + 1 file changed, 1 insertion(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index 7e721cba5aa..3b2cafc1623 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -11,6 +11,7 @@ * Added function to get actor' sockets names * 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) * Added possibility to change gravity variable in imui sensor for the accelerometer + * Fixed ROS2 native extension build error when ROS2 is installed in the system. ## CARLA 0.9.15 From cde95817ca55dc6fb55803bbb0b1b08c23221e12 Mon Sep 17 00:00:00 2001 From: xavisolesoft Date: Wed, 20 Mar 2024 08:23:37 +0000 Subject: [PATCH 06/11] ROS2Native: Force fast-dds dependencies download to avoid build crash when boost_asio and tinyxml2 are not installed in the system --- Util/BuildTools/Setup.sh | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Util/BuildTools/Setup.sh b/Util/BuildTools/Setup.sh index 21e8204fbd4..fc39ad00422 100755 --- a/Util/BuildTools/Setup.sh +++ b/Util/BuildTools/Setup.sh @@ -960,7 +960,8 @@ if ${USE_ROS2} ; then -DCMAKE_INSTALL_PREFIX="${FASTDDS_INSTALL_DIR}" \ -DCMAKE_CXX_FLAGS=-latomic \ -DCMAKE_CXX_FLAGS_RELEASE="-D_GLIBCXX_USE_CXX11_ABI=0" \ - \ + -DTHIRDPARTY_Asio=FORCE \ + -DTHIRDPARTY_TinyXML2=FORCE \ .. ninja ninja install From 2353b89a18bb4bed50c9e8651420df12efc65b19 Mon Sep 17 00:00:00 2001 From: xavisolesoft Date: Wed, 20 Mar 2024 08:26:19 +0000 Subject: [PATCH 07/11] Add change to the changelog --- CHANGELOG.md | 1 + 1 file changed, 1 insertion(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index 3b2cafc1623..3971470bd79 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -12,6 +12,7 @@ * 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) * Added possibility to change gravity variable in imui sensor for the accelerometer * Fixed ROS2 native extension build error when ROS2 is installed in the system. + * ROS2Native: Force fast-dds dependencies download to avoid build crash when boost_asio and tinyxml2 are not installed in Linux. ## CARLA 0.9.15 From 80af6025b3d6a86a979486d25d39561e9678b573 Mon Sep 17 00:00:00 2001 From: Kapler Date: Wed, 13 Mar 2024 17:33:21 +0800 Subject: [PATCH 08/11] Fix the misuse of the traci module in line 304 of sumo_simulation.py "sumolib" is not a submodule of "traci", which is why the error "module 'traci' has no attribute 'sumolib'" occurs. To fix this, remove the reference to "traci." --- Co-Simulation/Sumo/sumo_integration/sumo_simulation.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Co-Simulation/Sumo/sumo_integration/sumo_simulation.py b/Co-Simulation/Sumo/sumo_integration/sumo_simulation.py index 7756ff80a3a..22aeb7474e9 100644 --- a/Co-Simulation/Sumo/sumo_integration/sumo_simulation.py +++ b/Co-Simulation/Sumo/sumo_integration/sumo_simulation.py @@ -301,7 +301,7 @@ def _get_sumo_net(cfg_file): net_file = os.path.join(os.path.dirname(cfg_file), tag.get('value')) logging.debug('Reading net file: %s', net_file) - sumo_net = traci.sumolib.net.readNet(net_file) + sumo_net = sumolib.net.readNet(net_file) return sumo_net class SumoSimulation(object): From a12a137c86c753c29a16ccc0b7ebcc75e662a162 Mon Sep 17 00:00:00 2001 From: Axel Date: Thu, 22 Dec 2022 12:26:40 +0100 Subject: [PATCH 09/11] Added restore_physx_physics function --- LibCarla/source/carla/client/Vehicle.cpp | 4 ++ LibCarla/source/carla/client/Vehicle.h | 2 + .../source/carla/client/detail/Client.cpp | 4 ++ LibCarla/source/carla/client/detail/Client.h | 2 + .../source/carla/client/detail/Simulator.h | 4 ++ PythonAPI/carla/source/libcarla/Actor.cpp | 1 + PythonAPI/examples/manual_control_chrono.py | 23 ++++++++--- .../Carla/Source/Carla/Actor/CarlaActor.cpp | 22 +++++++++++ .../Carla/Source/Carla/Actor/CarlaActor.h | 7 ++++ .../Carla/Source/Carla/Server/CarlaServer.cpp | 24 ++++++++++++ .../BaseCarlaMovementComponent.h | 2 + .../CarSimManagerComponent.cpp | 39 +++++++------------ .../CarSimManagerComponent.h | 4 ++ .../ChronoMovementComponent.cpp | 8 +++- .../ChronoMovementComponent.h | 2 + 15 files changed, 117 insertions(+), 31 deletions(-) diff --git a/LibCarla/source/carla/client/Vehicle.cpp b/LibCarla/source/carla/client/Vehicle.cpp index 2e93489100c..4a0c2ebd403 100644 --- a/LibCarla/source/carla/client/Vehicle.cpp +++ b/LibCarla/source/carla/client/Vehicle.cpp @@ -144,6 +144,10 @@ namespace client { BaseJSONPath); } + void Vehicle::RestorePhysXPhysics() { + GetEpisode().Lock()->RestorePhysXPhysics(*this); + } + rpc::VehicleFailureState Vehicle::GetFailureState() const { return GetEpisode().Lock()->GetActorSnapshot(*this).state.vehicle_data.failure_state; } diff --git a/LibCarla/source/carla/client/Vehicle.h b/LibCarla/source/carla/client/Vehicle.h index cf5a37a173d..2fb7c2925df 100644 --- a/LibCarla/source/carla/client/Vehicle.h +++ b/LibCarla/source/carla/client/Vehicle.h @@ -137,6 +137,8 @@ namespace client { std::string TireJSON = "", std::string BaseJSONPath = ""); + void RestorePhysXPhysics(); + /// Returns the failure state of the vehicle rpc::VehicleFailureState GetFailureState() const; diff --git a/LibCarla/source/carla/client/detail/Client.cpp b/LibCarla/source/carla/client/detail/Client.cpp index b2715fcd9fc..fe5c327f0ee 100644 --- a/LibCarla/source/carla/client/detail/Client.cpp +++ b/LibCarla/source/carla/client/detail/Client.cpp @@ -528,6 +528,10 @@ namespace detail { BaseJSONPath); } + void Client::RestorePhysXPhysics(rpc::ActorId vehicle) { + _pimpl->AsyncCall("restore_physx_physics", vehicle); + } + void Client::ApplyControlToWalker(rpc::ActorId walker, const rpc::WalkerControl &control) { _pimpl->AsyncCall("apply_control_to_walker", walker, control); } diff --git a/LibCarla/source/carla/client/detail/Client.h b/LibCarla/source/carla/client/detail/Client.h index f776441827c..73f8cdb8534 100644 --- a/LibCarla/source/carla/client/detail/Client.h +++ b/LibCarla/source/carla/client/detail/Client.h @@ -331,6 +331,8 @@ namespace detail { std::string TireJSON, std::string BaseJSONPath); + void RestorePhysXPhysics(rpc::ActorId vehicle); + void ApplyControlToWalker( rpc::ActorId walker, const rpc::WalkerControl &control); diff --git a/LibCarla/source/carla/client/detail/Simulator.h b/LibCarla/source/carla/client/detail/Simulator.h index c6d529347ce..6f5d950c341 100644 --- a/LibCarla/source/carla/client/detail/Simulator.h +++ b/LibCarla/source/carla/client/detail/Simulator.h @@ -617,6 +617,10 @@ namespace detail { BaseJSONPath); } + void RestorePhysXPhysics(Vehicle &vehicle) { + _client.RestorePhysXPhysics(vehicle.GetId()); + } + /// @} // ========================================================================= /// @name Operations with the recorder diff --git a/PythonAPI/carla/source/libcarla/Actor.cpp b/PythonAPI/carla/source/libcarla/Actor.cpp index 3f9b4ef7e44..26d678460c4 100644 --- a/PythonAPI/carla/source/libcarla/Actor.cpp +++ b/PythonAPI/carla/source/libcarla/Actor.cpp @@ -203,6 +203,7 @@ void export_actor() { .def("enable_carsim", &cc::Vehicle::EnableCarSim, (arg("simfile_path") = "")) .def("use_carsim_road", &cc::Vehicle::UseCarSimRoad, (arg("enabled"))) .def("enable_chrono_physics", &cc::Vehicle::EnableChronoPhysics, (arg("max_substeps")=30, arg("max_substep_delta_time")=0.002, arg("vehicle_json")="", arg("powetrain_json")="", arg("tire_json")="", arg("base_json_path")="")) + .def("restore_physx_physics", &cc::Vehicle::RestorePhysXPhysics) .def("get_failure_state", &cc::Vehicle::GetFailureState) .def(self_ns::str(self_ns::self)) ; diff --git a/PythonAPI/examples/manual_control_chrono.py b/PythonAPI/examples/manual_control_chrono.py index ad453a6fe0c..f72bc7ecf02 100644 --- a/PythonAPI/examples/manual_control_chrono.py +++ b/PythonAPI/examples/manual_control_chrono.py @@ -324,6 +324,7 @@ class KeyboardControl(object): def __init__(self, world, start_in_autopilot): self._carsim_enabled = False self._carsim_road = False + self._chrono_enabled = False self._autopilot_enabled = start_in_autopilot if isinstance(world.player, carla.Vehicle): self._control = carla.VehicleControl() @@ -417,14 +418,24 @@ def parse_events(self, client, world, clock): world.camera_manager.set_sensor(current_index) elif event.key == K_k and (pygame.key.get_mods() & KMOD_CTRL): print("k pressed") - world.player.enable_carsim() + if not self._carsim_enabled: + self._carsim_enabled = True + world.player.enable_carsim() + else: + self._carsim_enabled = False + world.player.restore_physx_physics() elif event.key == K_o and (pygame.key.get_mods() & KMOD_CTRL): print("o pressed") - vehicle_json = "sedan/vehicle/Sedan_Vehicle.json" - powertrain_json = "sedan/powertrain/Sedan_SimpleMapPowertrain.json" - tire_json = "sedan/tire/Sedan_TMeasyTire.json" - base_path = "~/carla/Build/chrono-install/share/chrono/data/vehicle/" - world.player.enable_chrono_physics(5000, 0.002, vehicle_json, powertrain_json, tire_json, base_path) + if not self._chrono_enabled: + self._chrono_enabled = True + vehicle_json = "sedan/vehicle/Sedan_Vehicle.json" + powertrain_json = "sedan/powertrain/Sedan_SimpleMapPowertrain.json" + tire_json = "sedan/tire/Sedan_TMeasyTire.json" + base_path = "/home/adas/carla/Build/chrono-install/share/chrono/data/vehicle/" + world.player.enable_chrono_physics(5000, 0.002, vehicle_json, powertrain_json, tire_json, base_path) + else: + self._chrono_enabled = False + world.player.restore_physx_physics() elif event.key == K_j and (pygame.key.get_mods() & KMOD_CTRL): self._carsim_road = not self._carsim_road world.player.use_carsim_road(self._carsim_road) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.cpp index f9dacdc9144..dfec0bc43f1 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.cpp @@ -1055,6 +1055,28 @@ ECarlaServerResponse FVehicleActor::EnableChronoPhysics( return ECarlaServerResponse::Success; } +ECarlaServerResponse FVehicleActor::RestorePhysXPhysics() +{ + if (IsDormant()) + { + } + else + { + auto Vehicle = Cast(GetActor()); + if (Vehicle == nullptr) + { + return ECarlaServerResponse::NotAVehicle; + } + UBaseCarlaMovementComponent* MovementComponent = + Vehicle->GetCarlaMovementComponent(); + if(MovementComponent) + { + MovementComponent->DisableSpecialPhysics(); + } + } + return ECarlaServerResponse::Success; +} + // FSensorActor functions --------------------- // FtrafficSignActor functions --------------------- diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.h index ed3982727cf..f7edb4b4f97 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.h @@ -343,6 +343,11 @@ class FCarlaActor return ECarlaServerResponse::ActorTypeMismatch; } + virtual ECarlaServerResponse RestorePhysXPhysics() + { + return ECarlaServerResponse::ActorTypeMismatch; + } + // Traffic light functions virtual ECarlaServerResponse SetTrafficLightState(const ETrafficLightState&) @@ -532,6 +537,8 @@ class FVehicleActor : public FCarlaActor uint64_t MaxSubsteps, float MaxSubstepDeltaTime, const FString& VehicleJSON, const FString& PowertrainJSON, const FString& TireJSON, const FString& BaseJSONPath) final; + + virtual ECarlaServerResponse RestorePhysXPhysics(); }; class FSensorActor : public FCarlaActor diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp index 6d945ccf568..7824ddfde62 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp @@ -2319,6 +2319,30 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_ return R::Success(); }; + BIND_SYNC(restore_physx_physics) << [this]( + cr::ActorId ActorId) -> R + { + REQUIRE_CARLA_EPISODE(); + FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId); + if (!CarlaActor) + { + return RespondError( + "restore_physx_physics", + ECarlaServerResponse::ActorNotFound, + " Actor Id: " + FString::FromInt(ActorId)); + } + ECarlaServerResponse Response = + CarlaActor->RestorePhysXPhysics(); + if (Response != ECarlaServerResponse::Success) + { + return RespondError( + "restore_physx_physics", + Response, + " Actor Id: " + FString::FromInt(ActorId)); + } + return R::Success(); + }; + // ~~ Traffic lights ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ BIND_SYNC(set_traffic_light_state) << [this]( diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/BaseCarlaMovementComponent.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/BaseCarlaMovementComponent.h index 9a6c0b08459..509a64219ca 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/BaseCarlaMovementComponent.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/BaseCarlaMovementComponent.h @@ -35,6 +35,8 @@ class CARLA_API UBaseCarlaMovementComponent : public UMovementComponent virtual float GetVehicleForwardSpeed() const; + virtual void DisableSpecialPhysics() {}; + protected: void DisableUE4VehiclePhysics(); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/CarSimManagerComponent.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/CarSimManagerComponent.cpp index 505c5289edc..a63b9857c4d 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/CarSimManagerComponent.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/CarSimManagerComponent.cpp @@ -103,10 +103,7 @@ void UCarSimManagerComponent::ProcessControl(FVehicleControl &Control) #endif } -void UCarSimManagerComponent::OnCarSimHit(AActor *Actor, - AActor *OtherActor, - FVector NormalImpulse, - const FHitResult &Hit) +void UCarSimManagerComponent::DisableCarSimPhysics() { #ifdef WITH_CARSIM // finish Carsim simulation @@ -130,6 +127,19 @@ void UCarSimManagerComponent::OnCarSimHit(AActor *Actor, #endif } +void UCarSimManagerComponent::DisableSpecialPhysics() +{ + DisableCarSimPhysics(); +} + +void UCarSimManagerComponent::OnCarSimHit(AActor *Actor, + AActor *OtherActor, + FVector NormalImpulse, + const FHitResult &Hit) +{ + DisableCarSimPhysics(); +} + void UCarSimManagerComponent::OnCarSimOverlap(UPrimitiveComponent* OverlappedComponent, AActor* OtherActor, @@ -142,26 +152,7 @@ void UCarSimManagerComponent::OnCarSimOverlap(UPrimitiveComponent* OverlappedCom ECollisionChannel::ECC_WorldDynamic) == ECollisionResponse::ECR_Block) { - #ifdef WITH_CARSIM - // finish Carsim simulation - UDefaultMovementComponent::CreateDefaultMovementComponent(CarlaVehicle); - CarlaVehicle->GetMesh()->SetPhysicsLinearVelocity(FVector(0,0,0), false, "Vehicle_Base"); - CarlaVehicle->GetVehicleMovementComponent()->SetComponentTickEnabled(true); - CarlaVehicle->GetVehicleMovementComponent()->Activate(); - CarlaVehicle->GetMesh()->PhysicsTransformUpdateMode = EPhysicsTransformUpdateMode::SimulationUpatesComponentTransform; - auto * Bone = CarlaVehicle->GetMesh()->GetBodyInstance(NAME_None); - if (Bone) - { - Bone->SetInstanceSimulatePhysics(true); - } - else - { - carla::log_warning("No bone with name"); - } - CarlaVehicle->GetMesh()->SetCollisionResponseToChannel(ECollisionChannel::ECC_WorldStatic, ECollisionResponse::ECR_Block); - CarlaVehicle->GetMesh()->SetCollisionProfileName("Vehicle"); - CarlaVehicle->RestoreVehiclePhysicsControl(); - #endif + DisableCarSimPhysics(); } } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/CarSimManagerComponent.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/CarSimManagerComponent.h index c4f7ee42feb..0d7ab42158b 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/CarSimManagerComponent.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/CarSimManagerComponent.h @@ -52,6 +52,10 @@ class CARLA_API UCarSimManagerComponent : public UBaseCarlaMovementComponent float GetVehicleForwardSpeed() const override; + void DisableCarSimPhysics(); + + virtual void DisableSpecialPhysics() override; + private: // On car mesh hit, only works when carsim is enabled diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/ChronoMovementComponent.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/ChronoMovementComponent.cpp index 5250d88e1ab..5cac86c0e20 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/ChronoMovementComponent.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/ChronoMovementComponent.cpp @@ -348,6 +348,11 @@ void UChronoMovementComponent::EndPlay(const EEndPlayReason::Type EndPlayReason) } #endif +void UChronoMovementComponent::DisableSpecialPhysics() +{ + DisableChronoPhysics(); +} + void UChronoMovementComponent::DisableChronoPhysics() { this->SetComponentTickEnabled(false); @@ -358,7 +363,6 @@ void UChronoMovementComponent::DisableChronoPhysics() CarlaVehicle->GetMesh()->SetCollisionResponseToChannel( ECollisionChannel::ECC_WorldStatic, ECollisionResponse::ECR_Block); UDefaultMovementComponent::CreateDefaultMovementComponent(CarlaVehicle); - carla::log_warning("Chrono physics does not support collisions yet, reverting to default PhysX physics."); } void UChronoMovementComponent::OnVehicleHit(AActor *Actor, @@ -366,6 +370,7 @@ void UChronoMovementComponent::OnVehicleHit(AActor *Actor, FVector NormalImpulse, const FHitResult &Hit) { + carla::log_warning("Chrono physics does not support collisions yet, reverting to default PhysX physics."); DisableChronoPhysics(); } @@ -383,6 +388,7 @@ void UChronoMovementComponent::OnVehicleOverlap( ECollisionChannel::ECC_WorldDynamic) == ECollisionResponse::ECR_Block) { + carla::log_warning("Chrono physics does not support collisions yet, reverting to default PhysX physics."); DisableChronoPhysics(); } } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/ChronoMovementComponent.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/ChronoMovementComponent.h index 68e86f4d1cd..600cf0f3ea9 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/ChronoMovementComponent.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/MovementComponents/ChronoMovementComponent.h @@ -101,6 +101,8 @@ class CARLA_API UChronoMovementComponent : public UBaseCarlaMovementComponent virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override; #endif + virtual void DisableSpecialPhysics() override; + private: void DisableChronoPhysics(); From b6b4b4f138e55409885b5455e18795df4f4e0aa6 Mon Sep 17 00:00:00 2001 From: Michal Sojka Date: Thu, 22 Feb 2024 13:20:05 +0100 Subject: [PATCH 10/11] libcarla: Fix compile error with gcc >=13 The error was: LibCarla/source/carla/client/FileTransfer.h:31:57: error: 'uint8_t' was not declared in this scope 31 | static bool WriteFile(std::string path, std::vector content); | ^~~~~~~ --- LibCarla/source/carla/client/FileTransfer.h | 1 + 1 file changed, 1 insertion(+) diff --git a/LibCarla/source/carla/client/FileTransfer.h b/LibCarla/source/carla/client/FileTransfer.h index fd1c091621f..8bfa00ca17f 100644 --- a/LibCarla/source/carla/client/FileTransfer.h +++ b/LibCarla/source/carla/client/FileTransfer.h @@ -12,6 +12,7 @@ #include #include #include +#include namespace carla { namespace client { From d5d3cf9edf0f4857e2e9c43e6396bd0828f999f5 Mon Sep 17 00:00:00 2001 From: Olli Koskelainen Date: Wed, 27 Mar 2024 13:28:43 +0200 Subject: [PATCH 11/11] Debug drawing extension to allow drawing primitives on HUD layer (#7168) * Extended debug draw functions to allow drawing primitives on HUD layer * Added documentation for new drawing features * Added debug draw changes to changelog --------- Co-authored-by: Olli --- CHANGELOG.md | 1 + Docs/python_api.md | 514 ++++++++++-------- LibCarla/source/carla/client/DebugHelper.cpp | 45 ++ LibCarla/source/carla/client/DebugHelper.h | 32 ++ LibCarla/source/carla/rpc/DebugShape.h | 28 +- PythonAPI/carla/source/libcarla/World.cpp | 30 + PythonAPI/docs/world.yml | 136 ++++- .../Carla/Source/Carla/Game/CarlaHUD.cpp | 27 +- .../Carla/Source/Carla/Game/CarlaHUD.h | 11 + .../Source/Carla/Util/DebugShapeDrawer.cpp | 209 ++++--- 10 files changed, 717 insertions(+), 316 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 3971470bd79..0475512ba7c 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -10,6 +10,7 @@ * make PythonAPI Windows: Fixed incompatibility issue with Anaconda due `py` command. * Added function to get actor' sockets names * 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) + * Extended debug drawing functions to allow drawing primitives on HUD layer * Added possibility to change gravity variable in imui sensor for the accelerometer * Fixed ROS2 native extension build error when ROS2 is installed in the system. * ROS2Native: Force fast-dds dependencies download to avoid build crash when boost_asio and tinyxml2 are not installed in Linux. diff --git a/Docs/python_api.md b/Docs/python_api.md index 617d8518ea5..88c0ae748de 100644 --- a/Docs/python_api.md +++ b/Docs/python_api.md @@ -722,13 +722,45 @@ Draws an arrow from `begin` to `end` pointing in that direction. - `color` (_[carla.Color](#carla.Color)_) - RGB code to color the object. Red by default. - `life_time` (_float - seconds_) - Shape's lifespan. By default it only lasts one frame. Set this to 0 for permanent shapes. - **draw_box**(**self**, **box**, **rotation**, **thickness**=0.1, **color**=(255,0,0), **life_time**=-1.0) -Draws a box, ussually to act for object colliders. +Draws a box, usually to act for object colliders. - **Parameters:** - `box` (_[carla.BoundingBox](#carla.BoundingBox)_) - Object containing a location and the length of a box for every axis. - `rotation` (_[carla.Rotation](#carla.Rotation) - degrees (pitch,yaw,roll)_) - Orientation of the box according to Unreal Engine's axis system. - `thickness` (_float - meters_) - Density of the lines that define the box. - `color` (_[carla.Color](#carla.Color)_) - RGB code to color the object. Red by default. - `life_time` (_float - seconds_) - Shape's lifespan. By default it only lasts one frame. Set this to 0 for permanent shapes. +- **draw_hud_arrow**(**self**, **begin**, **end**, **thickness**=0.1, **arrow_size**=0.1, **color**=(255,0,0), **life_time**=-1.0) +Draws an arrow on the HUD from `begin` to `end` which can only be seen server-side. + - **Parameters:** + - `begin` (_[carla.Location](#carla.Location) - meters_) - Point in the coordinate system where the arrow starts. + - `end` (_[carla.Location](#carla.Location) - meters_) - Point in the coordinate system where the arrow ends and points towards to. + - `thickness` (_float - meters_) - Density of the line. + - `arrow_size` (_float - meters_) - Size of the tip of the arrow. + - `color` (_[carla.Color](#carla.Color)_) - RGB code to color the object. Red by default. + - `life_time` (_float - seconds_) - Shape's lifespan. By default it only lasts one frame. Set this to 0 for permanent shapes. +- **draw_hud_box**(**self**, **box**, **rotation**, **thickness**=0.1, **color**=(255,0,0), **life_time**=-1.0) +Draws a box on the HUD, usually to act for object colliders. The box can only be seen server-side. + - **Parameters:** + - `box` (_[carla.BoundingBox](#carla.BoundingBox)_) - Object containing a location and the length of a box for every axis. + - `rotation` (_[carla.Rotation](#carla.Rotation) - degrees (pitch,yaw,roll)_) - Orientation of the box according to Unreal Engine's axis system. + - `thickness` (_float - meters_) - Density of the lines that define the box. + - `color` (_[carla.Color](#carla.Color)_) - RGB code to color the object. Red by default. + - `life_time` (_float - seconds_) - Shape's lifespan. By default it only lasts one frame. Set this to 0 for permanent shapes. +- **draw_hud_line**(**self**, **begin**, **end**, **thickness**=0.1, **color**=(255,0,0), **life_time**=-1.0) +Draws a line on the HUD in between `begin` and `end`. The line can only be seen server-side. + - **Parameters:** + - `begin` (_[carla.Location](#carla.Location) - meters_) - Point in the coordinate system where the line starts. + - `end` (_[carla.Location](#carla.Location) - meters_) - Spot in the coordinate system where the line ends. + - `thickness` (_float - meters_) - Density of the line. + - `color` (_[carla.Color](#carla.Color)_) - RGB code to color the object. Red by default. + - `life_time` (_float - seconds_) - Shape's lifespan. By default it only lasts one frame. Set this to 0 for permanent shapes. +- **draw_hud_point**(**self**, **location**, **size**=0.1, **color**=(255,0,0), **life_time**=-1.0) +Draws a point on the HUD at `location`. The point can only be seen server-side. + - **Parameters:** + - `location` (_[carla.Location](#carla.Location) - meters_) - Spot in the coordinate system to center the object. + - `size` (_float - meters_) - Density of the point. + - `color` (_[carla.Color](#carla.Color)_) - RGB code to color the object. Red by default. + - `life_time` (_float - seconds_) - Shape's lifespan. By default it only lasts one frame. Set this to 0 for permanent shapes. - **draw_line**(**self**, **begin**, **end**, **thickness**=0.1, **color**=(255,0,0), **life_time**=-1.0) Draws a line in between `begin` and `end`. - **Parameters:** @@ -4194,71 +4226,6 @@ document.getElementById("snipets-container").innerHTML = null; } -