From e6ba65db2190856d319491687d549070a87609a3 Mon Sep 17 00:00:00 2001 From: Blyron Date: Thu, 30 May 2024 14:59:57 +0200 Subject: [PATCH 01/19] Uses switches depending on line type --- LibCarla/source/carla/road/MeshFactory.cpp | 145 +++++++++++++++------ LibCarla/source/carla/road/MeshFactory.h | 10 +- 2 files changed, 113 insertions(+), 42 deletions(-) diff --git a/LibCarla/source/carla/road/MeshFactory.cpp b/LibCarla/source/carla/road/MeshFactory.cpp index 8d7019ebb..0c2d08515 100644 --- a/LibCarla/source/carla/road/MeshFactory.cpp +++ b/LibCarla/source/carla/road/MeshFactory.cpp @@ -206,23 +206,33 @@ namespace geom { size_t PosToAdd = it - redirections.begin(); Mesh out_mesh; - if(lane_pair.second.GetType() == road::Lane::LaneType::Driving ){ - out_mesh += *GenerateTesselated(lane_pair.second); - }else{ - out_mesh += *GenerateSidewalk(lane_pair.second); + switch(lane_pair.second.GetType()) + { + case road::Lane::LaneType::Driving: + case road::Lane::LaneType::Parking: + case road::Lane::LaneType::Bidirectional: + { + out_mesh += *GenerateTesselated(lane_pair.second); + break; + } + case road::Lane::LaneType::Shoulder: + case road::Lane::LaneType::Sidewalk: + case road::Lane::LaneType::Biking: + { + out_mesh += *GenerateSidewalk(lane_pair.second); + break; + } + default: + { + out_mesh += *GenerateTesselated(lane_pair.second); + break; + } } if( result[lane_pair.second.GetType()].size() <= PosToAdd ){ result[lane_pair.second.GetType()].push_back(std::make_unique(out_mesh)); } else { - uint32_t verticesinwidth = 0; - if(lane_pair.second.GetType() == road::Lane::LaneType::Driving) { - verticesinwidth = vertices_in_width; - }else if(lane_pair.second.GetType() == road::Lane::LaneType::Sidewalk){ - verticesinwidth = 6; - }else{ - verticesinwidth = 2; - } + uint32_t verticesinwidth = SelectVerticesInWidth(vertices_in_width, lane_pair.second.GetType()); (result[lane_pair.second.GetType()][PosToAdd])->ConcatMesh(out_mesh, verticesinwidth); } } @@ -548,12 +558,28 @@ std::map>> MeshFactory: for (auto &&lane_pair : lane_section.GetLanes()) { Mesh lane_section_mesh; - if(lane_pair.second.GetType() == road::Lane::LaneType::Driving ){ - lane_section_mesh += *GenerateTesselated(lane_pair.second, s_current, s_until); - }else{ - lane_section_mesh += *GenerateSidewalk(lane_pair.second, s_current, s_until); + switch(lane_pair.second.GetType()) + { + case road::Lane::LaneType::Driving: + case road::Lane::LaneType::Parking: + case road::Lane::LaneType::Bidirectional: + { + lane_section_mesh += *GenerateTesselated(lane_pair.second, s_current, s_until); + break; + } + case road::Lane::LaneType::Shoulder: + case road::Lane::LaneType::Sidewalk: + case road::Lane::LaneType::Biking: + { + lane_section_mesh += *GenerateSidewalk(lane_pair.second, s_current, s_until); + break; + } + default: + { + lane_section_mesh += *GenerateTesselated(lane_pair.second, s_current, s_until); + break; + } } - auto it = std::find(redirections.begin(), redirections.end(), lane_pair.first); if (it == redirections.end()) { redirections.push_back(lane_pair.first); @@ -564,14 +590,7 @@ std::map>> MeshFactory: if (mesh_uptr_list[lane_pair.second.GetType()].size() <= PosToAdd) { mesh_uptr_list[lane_pair.second.GetType()].push_back(std::make_unique(lane_section_mesh)); } else { - uint32_t verticesinwidth = 0; - if(lane_pair.second.GetType() == road::Lane::LaneType::Driving) { - verticesinwidth = vertices_in_width; - }else if(lane_pair.second.GetType() == road::Lane::LaneType::Sidewalk){ - verticesinwidth = 6; - }else{ - verticesinwidth = 2; - } + uint32_t verticesinwidth = SelectVerticesInWidth(vertices_in_width, lane_pair.second.GetType()); (mesh_uptr_list[lane_pair.second.GetType()][PosToAdd])->ConcatMesh(lane_section_mesh, verticesinwidth); } } @@ -580,10 +599,27 @@ std::map>> MeshFactory: if (s_end - s_current > EPSILON) { for (auto &&lane_pair : lane_section.GetLanes()) { Mesh lane_section_mesh; - if(lane_pair.second.GetType() == road::Lane::LaneType::Driving ){ - lane_section_mesh += *GenerateTesselated(lane_pair.second, s_current, s_end); - }else{ - lane_section_mesh += *GenerateSidewalk(lane_pair.second, s_current, s_end); + switch(lane_pair.second.GetType()) + { + case road::Lane::LaneType::Driving: + case road::Lane::LaneType::Parking: + case road::Lane::LaneType::Bidirectional: + { + lane_section_mesh += *GenerateTesselated(lane_pair.second, s_current, s_end); + break; + } + case road::Lane::LaneType::Shoulder: + case road::Lane::LaneType::Sidewalk: + case road::Lane::LaneType::Biking: + { + lane_section_mesh += *GenerateSidewalk(lane_pair.second, s_current, s_end); + break; + } + default: + { + lane_section_mesh += *GenerateTesselated(lane_pair.second, s_current, s_end); + break; + } } auto it = std::find(redirections.begin(), redirections.end(), lane_pair.first); @@ -598,13 +634,7 @@ std::map>> MeshFactory: mesh_uptr_list[lane_pair.second.GetType()].push_back(std::make_unique(lane_section_mesh)); } else { uint32_t verticesinwidth = 0; - if(lane_pair.second.GetType() == road::Lane::LaneType::Driving) { - verticesinwidth = vertices_in_width; - }else if(lane_pair.second.GetType() == road::Lane::LaneType::Sidewalk){ - verticesinwidth = 6; - }else{ - verticesinwidth = 2; - } + *(mesh_uptr_list[lane_pair.second.GetType()][PosToAdd]) += lane_section_mesh; } } @@ -725,9 +755,20 @@ std::map>> MeshFactory: for (auto&& lane_section : road.GetLaneSections()) { for (auto&& lane : lane_section.GetLanes()) { if (lane.first != 0) { - if(lane.second.GetType() == road::Lane::LaneType::Driving ){ - GenerateLaneMarksForNotCenterLine(lane_section, lane.second, inout, outinfo); - outinfo.push_back("white"); + switch(lane.second.GetType()) + { + case road::Lane::LaneType::Driving: + case road::Lane::LaneType::Parking: + case road::Lane::LaneType::Bidirectional: + { + GenerateLaneMarksForNotCenterLine(lane_section, lane.second, inout, outinfo); + outinfo.push_back("white"); + break; + } + default: + { + break; + } } } else { if(lane.second.GetType() == road::Lane::LaneType::None ){ @@ -1131,6 +1172,32 @@ std::map>> MeshFactory: return std::make_unique(out_mesh); } + uint32_t MeshFactory::SelectVerticesInWidth(uint32_t default_num_vertices, road::Lane::LaneType type) + { + switch(type) + { + case road::Lane::LaneType::Driving: + case road::Lane::LaneType::Parking: + case road::Lane::LaneType::Bidirectional: + { + return default_num_vertices; + break; + } + case road::Lane::LaneType::Shoulder: + case road::Lane::LaneType::Sidewalk: + case road::Lane::LaneType::Biking: + { + return 6; + break; + } + default: + { + return 2; + break; + } + } + } + std::pair MeshFactory::ComputeEdgesForLanemark( const road::LaneSection& lane_section, const road::Lane& lane, diff --git a/LibCarla/source/carla/road/MeshFactory.h b/LibCarla/source/carla/road/MeshFactory.h index 42bc60ea1..00d3a712e 100644 --- a/LibCarla/source/carla/road/MeshFactory.h +++ b/LibCarla/source/carla/road/MeshFactory.h @@ -129,9 +129,7 @@ namespace geom { const road::Lane& lane, std::vector>& inout, std::vector& outinfo ) const; - // ========================================================================= - // -- Generation parameters ------------------------------------------------ - // ========================================================================= + /// Parameters for the road generation struct RoadParameters { @@ -148,6 +146,12 @@ namespace geom { RoadParameters road_param; + + // ========================================================================= + // -- Helper functions ------------------------------------------------ + // ========================================================================= + + static uint32_t SelectVerticesInWidth(uint32_t default_num_vertices, road::Lane::LaneType type); private: // Calculate the points on both sides of the lane mark for the specified s_current From e7d13e6c0e873eb26c6843162706635d937b4e9f Mon Sep 17 00:00:00 2001 From: Blyron Date: Thu, 30 May 2024 15:03:31 +0200 Subject: [PATCH 02/19] Removed unused variable --- LibCarla/source/carla/road/MeshFactory.cpp | 2 -- LibCarla/source/carla/road/MeshFactory.h | 5 ++++- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/LibCarla/source/carla/road/MeshFactory.cpp b/LibCarla/source/carla/road/MeshFactory.cpp index 0c2d08515..92627a79c 100644 --- a/LibCarla/source/carla/road/MeshFactory.cpp +++ b/LibCarla/source/carla/road/MeshFactory.cpp @@ -633,8 +633,6 @@ std::map>> MeshFactory: if (mesh_uptr_list[lane_pair.second.GetType()].size() <= PosToAdd) { mesh_uptr_list[lane_pair.second.GetType()].push_back(std::make_unique(lane_section_mesh)); } else { - uint32_t verticesinwidth = 0; - *(mesh_uptr_list[lane_pair.second.GetType()][PosToAdd]) += lane_section_mesh; } } diff --git a/LibCarla/source/carla/road/MeshFactory.h b/LibCarla/source/carla/road/MeshFactory.h index 00d3a712e..aacb07584 100644 --- a/LibCarla/source/carla/road/MeshFactory.h +++ b/LibCarla/source/carla/road/MeshFactory.h @@ -129,7 +129,10 @@ namespace geom { const road::Lane& lane, std::vector>& inout, std::vector& outinfo ) const; - + + // ========================================================================= + // -- Generation parameters ------------------------------------------------ + // ========================================================================= /// Parameters for the road generation struct RoadParameters { From 317037a31eaa1d2e96226ee5e342b912967ded06 Mon Sep 17 00:00:00 2001 From: Blyron <53337103+Blyron@users.noreply.github.com> Date: Fri, 31 May 2024 09:42:30 +0200 Subject: [PATCH 03/19] Removing useless code MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Xavier Solé Nogués --- LibCarla/source/carla/road/MeshFactory.cpp | 7 ------- 1 file changed, 7 deletions(-) diff --git a/LibCarla/source/carla/road/MeshFactory.cpp b/LibCarla/source/carla/road/MeshFactory.cpp index 92627a79c..b01828915 100644 --- a/LibCarla/source/carla/road/MeshFactory.cpp +++ b/LibCarla/source/carla/road/MeshFactory.cpp @@ -763,10 +763,6 @@ std::map>> MeshFactory: outinfo.push_back("white"); break; } - default: - { - break; - } } } else { if(lane.second.GetType() == road::Lane::LaneType::None ){ @@ -1179,19 +1175,16 @@ std::map>> MeshFactory: case road::Lane::LaneType::Bidirectional: { return default_num_vertices; - break; } case road::Lane::LaneType::Shoulder: case road::Lane::LaneType::Sidewalk: case road::Lane::LaneType::Biking: { return 6; - break; } default: { return 2; - break; } } } From 6aed213f3622dff6dac8bc6cf96193013b3188de Mon Sep 17 00:00:00 2001 From: LuisPovedaCano Date: Fri, 31 May 2024 10:01:30 +0200 Subject: [PATCH 04/19] fixed lidar in replayer mode with vehicles and walkers --- .../Carla/Source/Carla/Recorder/CarlaReplayerHelper.cpp | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaReplayerHelper.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaReplayerHelper.cpp index 65f37f975..8b1ff4282 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaReplayerHelper.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaReplayerHelper.cpp @@ -202,7 +202,7 @@ std::pair CarlaReplayerHelper::ProcessReplayerEventAdd( } // check to ignore Hero or Spectator - if ((bIgnoreHero && IsHero) || + if ((bIgnoreHero && IsHero) || (bIgnoreSpectator && ActorDesc.Id.StartsWith("spectator"))) { return std::make_pair(3, 0); @@ -227,7 +227,11 @@ std::pair CarlaReplayerHelper::ProcessReplayerEventAdd( // disable physics SetActorSimulatePhysics(result.second, false); // disable collisions - result.second->GetActor()->SetActorEnableCollision(false); + result.second->GetActor()->SetActorEnableCollision(true); + auto RootComponent = Cast( + result.second->GetActor()->GetRootComponent()); + RootComponent->SetSimulatePhysics(false); + RootComponent->SetCollisionEnabled(ECollisionEnabled::NoCollision); // disable autopilot for vehicles if (result.second->GetActorType() == FCarlaActor::ActorType::Vehicle) SetActorAutopilot(result.second, false, false); From d5c37f71b76462d23df9736a8efacdae30311d76 Mon Sep 17 00:00:00 2001 From: Daraan Date: Fri, 31 May 2024 12:04:04 +0200 Subject: [PATCH 05/19] Corrected information that Sensor.is_listening is a method (#7439) Co-authored-by: Blyron <53337103+Blyron@users.noreply.github.com> --- CHANGELOG.md | 1 + Docs/core_sensors.md | 3 ++- PythonAPI/carla/source/libcarla/Sensor.cpp | 1 - PythonAPI/docs/sensor.yml | 13 ++++++------- 4 files changed, 9 insertions(+), 9 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index ed7c3b58c..d04ec9fc3 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -14,6 +14,7 @@ * 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. + * PythonAPI `Sensor.is_listening` was defined twice (property and method), cleaned and clarified it as a method. * Added V2X sensors for cooperative awareness message and custom user-defined messages to support vehicle-to-vehicle communication ## CARLA 0.9.15 diff --git a/Docs/core_sensors.md b/Docs/core_sensors.md index 4ca9c1603..0a3ab237c 100644 --- a/Docs/core_sensors.md +++ b/Docs/core_sensors.md @@ -96,7 +96,8 @@ Sensor data differs a lot between sensor types. Take a look at the [sensors refe !!! Important - `is_listening` is a __sensor attribute__ that enables/disables data listening at will. + `is_listening()` is a __sensor method__ to check whether the sensor has a callback registered by `listen`. + `stop()` is a __sensor method__ to stop the sensor from listening. `sensor_tick` is a __blueprint attribute__ that sets the simulation time between data received. --- diff --git a/PythonAPI/carla/source/libcarla/Sensor.cpp b/PythonAPI/carla/source/libcarla/Sensor.cpp index 779738788..020b71592 100644 --- a/PythonAPI/carla/source/libcarla/Sensor.cpp +++ b/PythonAPI/carla/source/libcarla/Sensor.cpp @@ -26,7 +26,6 @@ void export_sensor() { namespace cc = carla::client; class_, boost::noncopyable, boost::shared_ptr>("Sensor", no_init) - .add_property("is_listening", &cc::Sensor::IsListening) .def("listen", &SubscribeToStream, (arg("callback"))) .def("is_listening", &cc::Sensor::IsListening) .def("stop", &cc::Sensor::Stop) diff --git a/PythonAPI/docs/sensor.yml b/PythonAPI/docs/sensor.yml index d1f118978..06e78c2a5 100644 --- a/PythonAPI/docs/sensor.yml +++ b/PythonAPI/docs/sensor.yml @@ -23,13 +23,6 @@ - [Collision detector](ref_sensors.md#collision-detector). - [Lane invasion detector](ref_sensors.md#lane-invasion-detector). - [Obstacle detector](ref_sensors.md#obstacle-detector). - - # - PROPERTIES ------------------------- - instance_variables: - - var_name: is_listening - type: boolean - doc: > - When True the sensor will be waiting for data. # - METHODS ---------------------------- methods: - def_name: listen @@ -44,6 +37,8 @@ - def_name: is_listening doc: > Returns whether the sensor is in a listening state. + return: + bool # -------------------------------------- - def_name: stop doc: > @@ -60,6 +55,8 @@ - def_name: is_enabled_for_ros doc: > Returns if the sensor is enabled or not to publish in ROS2 if there is no any listen to it. + return: + bool # -------------------------------------- - def_name: listen_to_gbuffer params: @@ -83,6 +80,8 @@ The ID of the target Unreal Engine GBuffer texture. doc: > Returns whether the sensor is in a listening state for a specific GBuffer texture. + return: + bool # -------------------------------------- - def_name: stop_gbuffer params: From 01b1ede51ac463fb59192a7a6bea8f6cda818b04 Mon Sep 17 00:00:00 2001 From: joel-mb Date: Fri, 31 May 2024 13:36:46 +0200 Subject: [PATCH 06/19] Expose Telemetry Data (#5153) * expose telemetry data to the client * CHANGELOG updated * minor fixes * Added new telemetry parameters: * Exposed omega instead of rpm * Added tire_load, normalized_long_force, normalized_lat_force --------- Co-authored-by: Blyron <53337103+Blyron@users.noreply.github.com> --- CHANGELOG.md | 2 + LibCarla/source/carla/client/Vehicle.cpp | 4 + LibCarla/source/carla/client/Vehicle.h | 7 + .../source/carla/client/detail/Client.cpp | 5 + LibCarla/source/carla/client/detail/Client.h | 3 + .../source/carla/client/detail/Simulator.h | 4 + .../source/carla/rpc/VehicleTelemetryData.h | 123 ++++++++++++++++++ .../source/carla/rpc/WheelTelemetryData.h | 120 +++++++++++++++++ PythonAPI/carla/source/libcarla/Actor.cpp | 1 + PythonAPI/carla/source/libcarla/Control.cpp | 123 ++++++++++++++++++ .../Carla/Source/Carla/Actor/CarlaActor.cpp | 19 +++ .../Carla/Source/Carla/Actor/CarlaActor.h | 8 ++ .../Carla/Source/Carla/Server/CarlaServer.cpp | 26 ++++ .../Carla/Vehicle/CarlaWheeledVehicle.cpp | 50 +++++++ .../Carla/Vehicle/CarlaWheeledVehicle.h | 4 + .../Carla/Vehicle/VehicleTelemetryData.h | 78 +++++++++++ 16 files changed, 577 insertions(+) create mode 100644 LibCarla/source/carla/rpc/VehicleTelemetryData.h create mode 100644 LibCarla/source/carla/rpc/WheelTelemetryData.h create mode 100644 Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/VehicleTelemetryData.h diff --git a/CHANGELOG.md b/CHANGELOG.md index d04ec9fc3..bde484631 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -14,9 +14,11 @@ * 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. + * Added API function `get_telemetry_data` to the vehicle actor. * PythonAPI `Sensor.is_listening` was defined twice (property and method), cleaned and clarified it as a method. * Added V2X sensors for cooperative awareness message and custom user-defined messages to support vehicle-to-vehicle communication + ## CARLA 0.9.15 * Added Digital Twins feature version 0.1. Now you can create your own map based on OpenStreetMaps diff --git a/LibCarla/source/carla/client/Vehicle.cpp b/LibCarla/source/carla/client/Vehicle.cpp index 4a0c2ebd4..b24347e07 100644 --- a/LibCarla/source/carla/client/Vehicle.cpp +++ b/LibCarla/source/carla/client/Vehicle.cpp @@ -44,6 +44,10 @@ namespace client { } } + Vehicle::TelemetryData Vehicle::GetTelemetryData() const { + return GetEpisode().Lock()->GetVehicleTelemetryData(*this); + } + void Vehicle::ShowDebugTelemetry(bool enabled) { GetEpisode().Lock()->ShowVehicleDebugTelemetry(*this, enabled); } diff --git a/LibCarla/source/carla/client/Vehicle.h b/LibCarla/source/carla/client/Vehicle.h index 2fb7c2925..b9fe883a0 100644 --- a/LibCarla/source/carla/client/Vehicle.h +++ b/LibCarla/source/carla/client/Vehicle.h @@ -14,6 +14,7 @@ #include "carla/rpc/VehicleDoor.h" #include "carla/rpc/VehicleLightState.h" #include "carla/rpc/VehiclePhysicsControl.h" +#include "carla/rpc/VehicleTelemetryData.h" #include "carla/rpc/VehicleWheels.h" #include "carla/trafficmanager/TrafficManager.h" @@ -35,6 +36,7 @@ namespace client { using Control = rpc::VehicleControl; using AckermannControl = rpc::VehicleAckermannControl; using PhysicsControl = rpc::VehiclePhysicsControl; + using TelemetryData = rpc::VehicleTelemetryData; using LightState = rpc::VehicleLightState::LightState; using TM = traffic_manager::TrafficManager; using VehicleDoor = rpc::VehicleDoor; @@ -46,6 +48,11 @@ namespace client { /// Switch on/off this vehicle's autopilot. void SetAutopilot(bool enabled = true, uint16_t tm_port = TM_DEFAULT_PORT); + /// Return the telemetry data for this vehicle. + /// + /// @warning This function does call the simulator. + TelemetryData GetTelemetryData() const; + /// Switch on/off this vehicle's autopilot. void ShowDebugTelemetry(bool enabled = true); diff --git a/LibCarla/source/carla/client/detail/Client.cpp b/LibCarla/source/carla/client/detail/Client.cpp index 72b9e705e..49cf59e00 100644 --- a/LibCarla/source/carla/client/detail/Client.cpp +++ b/LibCarla/source/carla/client/detail/Client.cpp @@ -481,6 +481,11 @@ namespace detail { _pimpl->AsyncCall("set_actor_autopilot", vehicle, enabled); } + rpc::VehicleTelemetryData Client::GetVehicleTelemetryData( + rpc::ActorId vehicle) const { + return _pimpl->CallAndWait("get_telemetry_data", vehicle); + } + void Client::ShowVehicleDebugTelemetry(rpc::ActorId vehicle, const bool enabled) { _pimpl->AsyncCall("show_vehicle_debug_telemetry", vehicle, enabled); } diff --git a/LibCarla/source/carla/client/detail/Client.h b/LibCarla/source/carla/client/detail/Client.h index 064cd2c86..ffd3c8fba 100644 --- a/LibCarla/source/carla/client/detail/Client.h +++ b/LibCarla/source/carla/client/detail/Client.h @@ -29,6 +29,7 @@ #include "carla/rpc/VehicleLightStateList.h" #include "carla/rpc/VehicleLightState.h" #include "carla/rpc/VehiclePhysicsControl.h" +#include "carla/rpc/VehicleTelemetryData.h" #include "carla/rpc/VehicleWheels.h" #include "carla/rpc/WeatherParameters.h" #include "carla/rpc/Texture.h" @@ -285,6 +286,8 @@ namespace detail { rpc::ActorId vehicle, bool enabled); + rpc::VehicleTelemetryData GetVehicleTelemetryData(rpc::ActorId vehicle) const; + void ShowVehicleDebugTelemetry( rpc::ActorId vehicle, bool enabled); diff --git a/LibCarla/source/carla/client/detail/Simulator.h b/LibCarla/source/carla/client/detail/Simulator.h index 7dea3ced4..0ff8f3c17 100644 --- a/LibCarla/source/carla/client/detail/Simulator.h +++ b/LibCarla/source/carla/client/detail/Simulator.h @@ -525,6 +525,10 @@ namespace detail { _client.SetActorAutopilot(vehicle.GetId(), enabled); } + rpc::VehicleTelemetryData GetVehicleTelemetryData(const Vehicle &vehicle) const { + return _client.GetVehicleTelemetryData(vehicle.GetId()); + } + void ShowVehicleDebugTelemetry(Vehicle &vehicle, bool enabled = true) { _client.ShowVehicleDebugTelemetry(vehicle.GetId(), enabled); } diff --git a/LibCarla/source/carla/rpc/VehicleTelemetryData.h b/LibCarla/source/carla/rpc/VehicleTelemetryData.h new file mode 100644 index 000000000..7be84e8a3 --- /dev/null +++ b/LibCarla/source/carla/rpc/VehicleTelemetryData.h @@ -0,0 +1,123 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/MsgPack.h" +#include "carla/rpc/WheelTelemetryData.h" + +#include + +namespace carla { +namespace rpc { + class VehicleTelemetryData { + public: + + VehicleTelemetryData() = default; + + VehicleTelemetryData( + float speed, + float steer, + float throttle, + float brake, + float engine_rpm, + int32_t gear, + float drag, + std::vector wheels) + : speed(speed), + steer(steer), + throttle(throttle), + brake(brake), + engine_rpm(engine_rpm), + gear(gear), + drag(drag), + wheels(wheels) {} + + const std::vector &GetWheels() const { + return wheels; + } + + void SetWheels(std::vector &in_wheels) { + wheels = in_wheels; + } + + float speed = 0.0f; + float steer = 0.0f; + float throttle = 0.0f; + float brake = 0.0f; + float engine_rpm = 0.0f; + int32_t gear = 0.0f; + float drag = 0.0f; + std::vector wheels; + + bool operator!=(const VehicleTelemetryData &rhs) const { + return + speed != rhs.speed || + steer != rhs.steer || + throttle != rhs.throttle || + brake != rhs.brake || + engine_rpm != rhs.engine_rpm || + gear != rhs.gear || + drag != rhs.drag || + wheels != rhs.wheels; + } + + bool operator==(const VehicleTelemetryData &rhs) const { + return !(*this != rhs); + } + +#ifdef LIBCARLA_INCLUDED_FROM_UE4 + + VehicleTelemetryData(const FVehicleTelemetryData &TelemetryData) { + speed = TelemetryData.Speed; + steer = TelemetryData.Steer; + throttle = TelemetryData.Throttle; + brake = TelemetryData.Brake; + engine_rpm = TelemetryData.EngineRPM; + gear = TelemetryData.Gear; + drag = TelemetryData.Drag; + + // Wheels Setup + wheels = std::vector(); + for (const auto &Wheel : TelemetryData.Wheels) { + wheels.push_back(WheelTelemetryData(Wheel)); + } + } + + operator FVehicleTelemetryData() const { + FVehicleTelemetryData TelemetryData; + + TelemetryData.Speed = speed; + TelemetryData.Steer = steer; + TelemetryData.Throttle = throttle; + TelemetryData.Brake = brake; + TelemetryData.EngineRPM = engine_rpm; + TelemetryData.Gear = gear; + TelemetryData.Drag = drag; + + TArray Wheels; + for (const auto &wheel : wheels) { + Wheels.Add(FWheelTelemetryData(wheel)); + } + TelemetryData.Wheels = Wheels; + + return TelemetryData; + } + +#endif + + MSGPACK_DEFINE_ARRAY(speed, + steer, + throttle, + brake, + engine_rpm, + gear, + drag, + wheels); + }; + +} // namespace rpc +} // namespace carla diff --git a/LibCarla/source/carla/rpc/WheelTelemetryData.h b/LibCarla/source/carla/rpc/WheelTelemetryData.h new file mode 100644 index 000000000..ce7df7b10 --- /dev/null +++ b/LibCarla/source/carla/rpc/WheelTelemetryData.h @@ -0,0 +1,120 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/MsgPack.h" + +namespace carla { +namespace rpc { + + class WheelTelemetryData { + public: + + WheelTelemetryData() = default; + + WheelTelemetryData( + float tire_friction, + float lat_slip, + float long_slip, + float omega, + float tire_load, + float normalized_tire_load, + float torque, + float long_force, + float lat_force, + float normalized_long_force, + float normalized_lat_force) + : tire_friction(tire_friction), + lat_slip(lat_slip), + long_slip(long_slip), + omega(omega), + tire_load(tire_load), + normalized_tire_load(normalized_tire_load), + torque(torque), + long_force(long_force), + lat_force(lat_force), + normalized_long_force(normalized_long_force), + normalized_lat_force(normalized_lat_force) {} + + float tire_friction = 0.0f; + float lat_slip = 0.0f; + float long_slip = 0.0f; + float omega = 0.0f; + float tire_load = 0.0f; + float normalized_tire_load = 0.0f; + float torque = 0.0f; + float long_force = 0.0f; + float lat_force = 0.0f; + float normalized_long_force = 0.0f; + float normalized_lat_force = 0.0f; + + bool operator!=(const WheelTelemetryData &rhs) const { + return + tire_friction != rhs.tire_friction || + lat_slip != rhs.lat_slip || + long_slip != rhs.long_slip || + omega != rhs.omega || + tire_load != rhs.tire_load || + normalized_tire_load != rhs.normalized_tire_load || + torque != rhs.torque || + long_force != rhs.long_force || + lat_force != rhs.lat_force || + normalized_long_force != rhs.normalized_long_force || + normalized_lat_force != rhs.normalized_lat_force; + } + + bool operator==(const WheelTelemetryData &rhs) const { + return !(*this != rhs); + } +#ifdef LIBCARLA_INCLUDED_FROM_UE4 + + WheelTelemetryData(const FWheelTelemetryData &TelemetryData) + : tire_friction(TelemetryData.TireFriction), + lat_slip(TelemetryData.LatSlip), + long_slip(TelemetryData.LongSlip), + omega(TelemetryData.Omega), + tire_load(TelemetryData.TireLoad), + normalized_tire_load(TelemetryData.NormalizedTireLoad), + torque(TelemetryData.Torque), + long_force(TelemetryData.LongForce), + lat_force(TelemetryData.LatForce), + normalized_long_force(TelemetryData.NormalizedLongForce), + normalized_lat_force(TelemetryData.NormalizedLatForce) {} + + operator FWheelTelemetryData() const { + FWheelTelemetryData TelemetryData; + TelemetryData.TireFriction = tire_friction; + TelemetryData.LatSlip = lat_slip; + TelemetryData.LongSlip = long_slip; + TelemetryData.Omega = omega; + TelemetryData.TireLoad = tire_load; + TelemetryData.NormalizedTireLoad = normalized_tire_load; + TelemetryData.Torque = torque; + TelemetryData.LongForce = long_force; + TelemetryData.LatForce = lat_force; + TelemetryData.NormalizedLongForce = normalized_long_force; + TelemetryData.NormalizedLatForce = normalized_lat_force; + + return TelemetryData; + } +#endif + + MSGPACK_DEFINE_ARRAY(tire_friction, + lat_slip, + long_slip, + omega, + tire_load, + normalized_tire_load, + torque, + long_force, + lat_force, + normalized_long_force, + normalized_lat_force) + }; + +} // namespace rpc +} // namespace carla diff --git a/PythonAPI/carla/source/libcarla/Actor.cpp b/PythonAPI/carla/source/libcarla/Actor.cpp index 26d678460..62dbe05ea 100644 --- a/PythonAPI/carla/source/libcarla/Actor.cpp +++ b/PythonAPI/carla/source/libcarla/Actor.cpp @@ -195,6 +195,7 @@ void export_actor() { .def("apply_ackermann_controller_settings", &cc::Vehicle::ApplyAckermannControllerSettings, (arg("settings"))) .def("get_ackermann_controller_settings", CONST_CALL_WITHOUT_GIL(cc::Vehicle, GetAckermannControllerSettings)) .def("set_autopilot", CALL_WITHOUT_GIL_2(cc::Vehicle, SetAutopilot, bool, uint16_t), (arg("enabled") = true, arg("tm_port") = ctm::TM_DEFAULT_PORT)) + .def("get_telemetry_data", CONST_CALL_WITHOUT_GIL(cc::Vehicle, GetTelemetryData)) .def("show_debug_telemetry", &cc::Vehicle::ShowDebugTelemetry, (arg("enabled") = true)) .def("get_speed_limit", &cc::Vehicle::GetSpeedLimit) .def("get_traffic_light_state", &cc::Vehicle::GetTrafficLightState) diff --git a/PythonAPI/carla/source/libcarla/Control.cpp b/PythonAPI/carla/source/libcarla/Control.cpp index 98a0e9bfb..f0e8f5e5d 100644 --- a/PythonAPI/carla/source/libcarla/Control.cpp +++ b/PythonAPI/carla/source/libcarla/Control.cpp @@ -8,7 +8,9 @@ #include #include #include +#include #include +#include #include #include #include @@ -116,6 +118,33 @@ namespace rpc { return out; } + std::ostream &operator<<(std::ostream &out, const WheelTelemetryData &telemetry) { + out << "WheelTelemetryData(tire_friction=" << std::to_string(telemetry.tire_friction) + << ", lat_slip=" << std::to_string(telemetry.lat_slip) + << ", long_slip=" << std::to_string(telemetry.long_slip) + << ", omega=" << std::to_string(telemetry.omega) + << ", tire_load=" << std::to_string(telemetry.tire_load) + << ", normalized_tire_load=" << std::to_string(telemetry.normalized_tire_load) + << ", torque=" << std::to_string(telemetry.torque) + << ", long_force=" << std::to_string(telemetry.long_force) + << ", lat_force=" << std::to_string(telemetry.lat_force) + << ", normalized_long_force=" << std::to_string(telemetry.normalized_long_force) + << ", normalized_lat_force=" << std::to_string(telemetry.normalized_lat_force) << ')'; + return out; + } + + std::ostream &operator<<(std::ostream &out, const VehicleTelemetryData &telemetry) { + out << "VehicleTelemetryData(speed=" << std::to_string(telemetry.speed) + << ", steer=" << std::to_string(telemetry.steer) + << ", throttle=" << std::to_string(telemetry.throttle) + << ", brake=" << std::to_string(telemetry.brake) + << ", engine_rpm=" << std::to_string(telemetry.engine_rpm) + << ", gear=" << std::to_string(telemetry.gear) + << ", drag=" << std::to_string(telemetry.drag) + << ", wheels=" << telemetry.wheels << ')'; + return out; + } + std::ostream &operator<<(std::ostream &out, const AckermannControllerSettings &settings) { out << "AckermannControllerSettings(speed_kp=" << std::to_string(settings.speed_kp) << ", speed_ki=" << std::to_string(settings.speed_ki) @@ -264,6 +293,54 @@ boost::python::object VehiclePhysicsControl_init(boost::python::tuple args, boos return res; } +static auto GetWheelsTelemetry(const carla::rpc::VehicleTelemetryData &self) { + const auto &wheels = self.GetWheels(); + boost::python::object get_iter = boost::python::iterator>(); + boost::python::object iter = get_iter(wheels); + return boost::python::list(iter); +} + +static void SetWheelsTelemetry(carla::rpc::VehicleTelemetryData &self, const boost::python::list &list) { + std::vector wheels; + auto length = boost::python::len(list); + for (auto i = 0u; i < length; ++i) { + wheels.push_back(boost::python::extract(list[i])); + } + self.SetWheels(wheels); +} + +boost::python::object VehicleTelemetryData_init(boost::python::tuple args, boost::python::dict kwargs) { + // Args names + const uint32_t NUM_ARGUMENTS = 7; + const char *args_names[NUM_ARGUMENTS] = { + "speed", + "steer", + "throttle", + "brake", + "engine_rpm", + "gear", + "wheels" + }; + + boost::python::object self = args[0]; + args = boost::python::tuple(args.slice(1, boost::python::_)); + + auto res = self.attr("__init__")(); + if (len(args) > 0) { + for (unsigned int i = 0; i < len(args); ++i) { + self.attr(args_names[i]) = args[i]; + } + } + + for (unsigned int i = 0; i < NUM_ARGUMENTS; ++i) { + if (kwargs.contains(args_names[i])) { + self.attr(args_names[i]) = kwargs[args_names[i]]; + } + } + + return res; +} + static auto GetBonesTransform(const carla::rpc::WalkerBoneControlIn &self) { const std::vector &bone_transform_data = self.bone_transforms; boost::python::object get_iter = @@ -507,4 +584,50 @@ void export_control() { .def("__ne__", &cr::VehiclePhysicsControl::operator!=) .def(self_ns::str(self_ns::self)) ; + + class_("WheelTelemetryData") + .def(init( + (arg("tire_friction")=0.0f, + arg("lat_slip")=0.0f, + arg("long_slip")=0.0f, + arg("omega")=0.0f, + arg("tire_load")=0.0f, + arg("normalized_tire_load")=0.0f, + arg("torque")=0.0f, + arg("long_force")=0.0f, + arg("lat_force")=0.0f, + arg("normalized_long_force")=0.0f, + arg("normalized_lat_force")=0.0f))) + .def_readwrite("tire_friction", &cr::WheelTelemetryData::tire_friction) + .def_readwrite("lat_slip", &cr::WheelTelemetryData::lat_slip) + .def_readwrite("long_slip", &cr::WheelTelemetryData::long_slip) + .def_readwrite("omega", &cr::WheelTelemetryData::omega) + .def_readwrite("tire_load", &cr::WheelTelemetryData::tire_load) + .def_readwrite("normalized_tire_load", &cr::WheelTelemetryData::normalized_tire_load) + .def_readwrite("torque", &cr::WheelTelemetryData::torque) + .def_readwrite("long_force", &cr::WheelTelemetryData::long_force) + .def_readwrite("lat_force", &cr::WheelTelemetryData::lat_force) + .def_readwrite("normalized_long_force", &cr::WheelTelemetryData::normalized_long_force) + .def_readwrite("normalized_lat_force", &cr::WheelTelemetryData::normalized_lat_force) + .def("__eq__", &cr::WheelTelemetryData::operator==) + .def("__ne__", &cr::WheelTelemetryData::operator!=) + .def(self_ns::str(self_ns::self)) + ; + + class_("VehicleTelemetryData", no_init) + .def("__init__", raw_function(VehicleTelemetryData_init)) + .def(init<>()) + .def_readwrite("speed", &cr::VehicleTelemetryData::speed) + .def_readwrite("steer", &cr::VehicleTelemetryData::steer) + .def_readwrite("throttle", &cr::VehicleTelemetryData::throttle) + .def_readwrite("brake", &cr::VehicleTelemetryData::brake) + .def_readwrite("engine_rpm", &cr::VehicleTelemetryData::engine_rpm) + .def_readwrite("gear", &cr::VehicleTelemetryData::gear) + .def_readwrite("drag", &cr::VehicleTelemetryData::drag) + .add_property("wheels", &GetWheelsTelemetry, &SetWheelsTelemetry) + .def("__eq__", &cr::VehicleTelemetryData::operator==) + .def("__ne__", &cr::VehicleTelemetryData::operator!=) + .def(self_ns::str(self_ns::self)) + ; + } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.cpp index dfec0bc43..764f7849d 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.cpp @@ -969,6 +969,25 @@ ECarlaServerResponse FVehicleActor::SetActorAutopilot(bool bEnabled, bool bKeepS return ECarlaServerResponse::Success; } +ECarlaServerResponse FVehicleActor::GetVehicleTelemetryData(FVehicleTelemetryData& TelemetryData) +{ + if (IsDormant()) + { + FVehicleTelemetryData EmptyTelemetryData; + TelemetryData = EmptyTelemetryData; + } + else + { + auto Vehicle = Cast(GetActor()); + if (Vehicle == nullptr) + { + return ECarlaServerResponse::NotAVehicle; + } + TelemetryData = Vehicle->GetVehicleTelemetryData(); + } + return ECarlaServerResponse::Success; +} + ECarlaServerResponse FVehicleActor::ShowVehicleDebugTelemetry(bool bEnabled) { if (IsDormant()) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.h index f7edb4b4f..dcef99905 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.h @@ -9,6 +9,7 @@ #include "Carla/Actor/ActorInfo.h" #include "Carla/Actor/ActorData.h" #include "Carla/Vehicle/CarlaWheeledVehicle.h" +#include "Carla/Vehicle/VehicleTelemetryData.h" #include "Carla/Walker/WalkerController.h" #include "Carla/Traffic/TrafficLightState.h" @@ -322,6 +323,11 @@ public: return ECarlaServerResponse::ActorTypeMismatch; } + virtual ECarlaServerResponse GetVehicleTelemetryData(FVehicleTelemetryData&) + { + return ECarlaServerResponse::ActorTypeMismatch; + } + virtual ECarlaServerResponse ShowVehicleDebugTelemetry(bool) { return ECarlaServerResponse::ActorTypeMismatch; @@ -527,6 +533,8 @@ public: virtual ECarlaServerResponse SetActorAutopilot(bool bEnabled, bool bKeepState = false) final; + virtual ECarlaServerResponse GetVehicleTelemetryData(FVehicleTelemetryData&) final; + virtual ECarlaServerResponse ShowVehicleDebugTelemetry(bool bEnabled) final; virtual ECarlaServerResponse EnableCarSim(const FString& SimfilePath) final; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp index b5c20a919..215780a27 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp @@ -65,6 +65,7 @@ #include #include #include +#include #include #include #include @@ -2245,6 +2246,31 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_ return R::Success(); }; + BIND_SYNC(get_telemetry_data) << [this]( + cr::ActorId ActorId) -> R + { + REQUIRE_CARLA_EPISODE(); + FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId); + if (!CarlaActor) + { + return RespondError( + "get_telemetry_data", + ECarlaServerResponse::ActorNotFound, + " Actor Id: " + FString::FromInt(ActorId)); + } + FVehicleTelemetryData TelemetryData; + ECarlaServerResponse Response = + CarlaActor->GetVehicleTelemetryData(TelemetryData); + if (Response != ECarlaServerResponse::Success) + { + return RespondError( + "get_telemetry_data", + Response, + " Actor Id: " + FString::FromInt(ActorId)); + } + return cr::VehicleTelemetryData(TelemetryData); + }; + BIND_SYNC(show_vehicle_debug_telemetry) << [this]( cr::ActorId ActorId, bool bEnabled) -> R diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp index 22a025444..dbcc64449 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp @@ -814,6 +814,56 @@ void ACarlaWheeledVehicle::DeactivateVelocityControl() VelocityControl->Deactivate(); } +FVehicleTelemetryData ACarlaWheeledVehicle::GetVehicleTelemetryData() const +{ + FVehicleTelemetryData TelemetryData; + + auto *MovementComponent = GetVehicleMovement(); + + // Vehicle telemetry data + TelemetryData.Speed = GetVehicleForwardSpeed() / 100.0f; // From cm/s to m/s + TelemetryData.Steer = LastAppliedControl.Steer; + TelemetryData.Throttle = LastAppliedControl.Throttle; + TelemetryData.Brake = LastAppliedControl.Brake; + TelemetryData.EngineRPM = MovementComponent->GetEngineRotationSpeed(); + TelemetryData.Gear = GetVehicleCurrentGear(); + TelemetryData.Drag = MovementComponent->DebugDragMagnitude / 100.0f; // kg*cm/s2 to Kg*m/s2 + + // Wheels telemetry data + FPhysXVehicleManager* MyVehicleManager = FPhysXVehicleManager::GetVehicleManagerFromScene(GetWorld()->GetPhysicsScene()); + + SCOPED_SCENE_READ_LOCK(MyVehicleManager->GetScene()); + PxWheelQueryResult* WheelsStates = MyVehicleManager->GetWheelsStates_AssumesLocked(MovementComponent); + check(WheelsStates); + + TArray Wheels; + for (uint32 w = 0; w < MovementComponent->PVehicle->mWheelsSimData.getNbWheels(); ++w) + { + FWheelTelemetryData WheelTelemetryData; + + WheelTelemetryData.TireFriction = WheelsStates[w].tireFriction; + WheelTelemetryData.LatSlip = FMath::RadiansToDegrees(WheelsStates[w].lateralSlip); + WheelTelemetryData.LongSlip = WheelsStates[w].longitudinalSlip; + WheelTelemetryData.Omega = MovementComponent->PVehicle->mWheelsDynData.getWheelRotationSpeed(w); + + UVehicleWheel* Wheel = MovementComponent->Wheels[w]; + WheelTelemetryData.TireLoad = Wheel->DebugTireLoad / 100.0f; + WheelTelemetryData.NormalizedTireLoad = Wheel->DebugNormalizedTireLoad; + WheelTelemetryData.Torque = Wheel->DebugWheelTorque / (100.0f * 100.0f); // From cm2 to m2 + WheelTelemetryData.LongForce = Wheel->DebugLongForce / 100.f; + WheelTelemetryData.LatForce = Wheel->DebugLatForce / 100.f; + WheelTelemetryData.NormalizedLongForce = (FMath::Abs(WheelTelemetryData.LongForce)*WheelTelemetryData.NormalizedTireLoad) / (WheelTelemetryData.TireLoad); + WheelTelemetryData.NormalizedLatForce = (FMath::Abs(WheelTelemetryData.LatForce)*WheelTelemetryData.NormalizedTireLoad) / (WheelTelemetryData.TireLoad); + + Wheels.Add(WheelTelemetryData); + } + + TelemetryData.Wheels = Wheels; + + return TelemetryData; + +} + void ACarlaWheeledVehicle::ShowDebugTelemetry(bool Enabled) { if (GetWorld()->GetFirstPlayerController()) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h index 0f5b4fea8..ae10be15f 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h @@ -16,6 +16,7 @@ #include "Vehicle/VehicleLightState.h" #include "Vehicle/VehicleInputPriority.h" #include "Vehicle/VehiclePhysicsControl.h" +#include "Vehicle/VehicleTelemetryData.h" #include "VehicleVelocityControl.h" #include "WheeledVehicleMovementComponent4W.h" #include "WheeledVehicleMovementComponentNW.h" @@ -240,6 +241,9 @@ public: UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) void DeactivateVelocityControl(); + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) + FVehicleTelemetryData GetVehicleTelemetryData() const; + UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) void ShowDebugTelemetry(bool Enabled); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/VehicleTelemetryData.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/VehicleTelemetryData.h new file mode 100644 index 000000000..b5c5aeb0e --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/VehicleTelemetryData.h @@ -0,0 +1,78 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "VehicleTelemetryData.generated.h" + +USTRUCT(BlueprintType) +struct FWheelTelemetryData +{ + GENERATED_USTRUCT_BODY() + + UPROPERTY(Category = "Wheel Telemetry Data", EditAnywhere, BlueprintReadWrite) + float TireFriction = 0.0f; + + UPROPERTY(Category = "Wheel Telemetry Data", EditAnywhere, BlueprintReadWrite) + float LatSlip = 0.0f; // degrees + + UPROPERTY(Category = "Wheel Telemetry Data", EditAnywhere, BlueprintReadWrite) + float LongSlip = 0.0f; + + UPROPERTY(Category = "Wheel Telemetry Data", EditAnywhere, BlueprintReadWrite) + float Omega = 0.0f; + + UPROPERTY(Category = "Wheel Telemetry Data", EditAnywhere, BlueprintReadWrite) + float TireLoad = 0.0f; + + UPROPERTY(Category = "Wheel Telemetry Data", EditAnywhere, BlueprintReadWrite) + float NormalizedTireLoad = 0.0f; + + UPROPERTY(Category = "Wheel Telemetry Data", EditAnywhere, BlueprintReadWrite) + float Torque = 0.0f; // [Nm] + + UPROPERTY(Category = "Wheel Telemetry Data", EditAnywhere, BlueprintReadWrite) + float LongForce = 0.0f; // [N] + + UPROPERTY(Category = "Wheel Telemetry Data", EditAnywhere, BlueprintReadWrite) + float LatForce = 0.0f; // [N] + + UPROPERTY(Category = "Wheel Telemetry Data", EditAnywhere, BlueprintReadWrite) + float NormalizedLongForce = 0.0f; + + UPROPERTY(Category = "Wheel Telemetry Data", EditAnywhere, BlueprintReadWrite) + float NormalizedLatForce = 0.0f; +}; + +USTRUCT(BlueprintType) +struct CARLA_API FVehicleTelemetryData +{ + GENERATED_BODY() + + UPROPERTY(Category = "Vehicle Telemetry Data", EditAnywhere, BlueprintReadWrite) + float Speed = 0.0f; // [m/s] + + UPROPERTY(Category = "Vehicle Telemetry Data", EditAnywhere, BlueprintReadWrite) + float Steer = 0.0f; + + UPROPERTY(Category = "Vehicle Telemetry Data", EditAnywhere, BlueprintReadWrite) + float Throttle = 0.0f; + + UPROPERTY(Category = "Vehicle Telemetry Data", EditAnywhere, BlueprintReadWrite) + float Brake = 0.0f; + + UPROPERTY(Category = "Vehicle Telemetry Data", EditAnywhere, BlueprintReadWrite) + float EngineRPM = 0.0f; + + UPROPERTY(Category = "Vehicle Telemetry Data", EditAnywhere, BlueprintReadWrite) + int32 Gear = 0.0f; + + UPROPERTY(Category = "Vehicle Telemetry Data", EditAnywhere, BlueprintReadWrite) + float Drag = 0.0f; // [N] + + UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite) + TArray Wheels; +}; From a06ab08c4c213de1dc64801ab4ee11ff0bfcf96b Mon Sep 17 00:00:00 2001 From: Daraan Date: Fri, 31 May 2024 17:37:10 +0200 Subject: [PATCH 07/19] Named and type-hint supporting detection results for the python agents. (#7174) * Python agents: Created NamedTuple for Detection return types * Python 2.7 and <3.6 compatible code * Updated Changelog * removed print * Added file description * removed unnecessary line * Added Literal type hint for <3.8 Python --------- Co-authored-by: glopezdiest <58212725+glopezdiest@users.noreply.github.com> Co-authored-by: Blyron <53337103+Blyron@users.noreply.github.com> --- CHANGELOG.md | 1 + .../carla/agents/navigation/basic_agent.py | 20 ++++++----- PythonAPI/carla/agents/tools/hints.py | 34 +++++++++++++++++++ 3 files changed, 46 insertions(+), 9 deletions(-) create mode 100644 PythonAPI/carla/agents/tools/hints.py diff --git a/CHANGELOG.md b/CHANGELOG.md index bde484631..d743c9c7e 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -17,6 +17,7 @@ * Added API function `get_telemetry_data` to the vehicle actor. * PythonAPI `Sensor.is_listening` was defined twice (property and method), cleaned and clarified it as a method. * Added V2X sensors for cooperative awareness message and custom user-defined messages to support vehicle-to-vehicle communication + * Added named tuples for BasicAgent.py's detection result to allow for type-hints and better semantics. ## CARLA 0.9.15 diff --git a/PythonAPI/carla/agents/navigation/basic_agent.py b/PythonAPI/carla/agents/navigation/basic_agent.py index 44e6d0351..aeddc005e 100644 --- a/PythonAPI/carla/agents/navigation/basic_agent.py +++ b/PythonAPI/carla/agents/navigation/basic_agent.py @@ -18,6 +18,8 @@ from agents.tools.misc import (get_speed, is_within_distance, get_trafficlight_trigger_location, compute_distance) +from agents.tools.hints import ObstacleDetectionResult, TrafficLightDetectionResult + class BasicAgent(object): """ @@ -265,7 +267,7 @@ class BasicAgent(object): If None, the base threshold value is used """ if self._ignore_traffic_lights: - return (False, None) + return TrafficLightDetectionResult(False, None) if not lights_list: lights_list = self._world.get_actors().filter("*traffic_light*") @@ -277,7 +279,7 @@ class BasicAgent(object): if self._last_traffic_light.state != carla.TrafficLightState.Red: self._last_traffic_light = None else: - return (True, self._last_traffic_light) + return TrafficLightDetectionResult(True, self._last_traffic_light) ego_vehicle_location = self._vehicle.get_location() ego_vehicle_waypoint = self._map.get_waypoint(ego_vehicle_location) @@ -308,9 +310,9 @@ class BasicAgent(object): if is_within_distance(trigger_wp.transform, self._vehicle.get_transform(), max_distance, [0, 90]): self._last_traffic_light = traffic_light - return (True, traffic_light) + return TrafficLightDetectionResult(True, traffic_light) - return (False, None) + return TrafficLightDetectionResult(False, None) def _vehicle_obstacle_detected(self, vehicle_list=None, max_distance=None, up_angle_th=90, low_angle_th=0, lane_offset=0): """ @@ -347,12 +349,12 @@ class BasicAgent(object): return Polygon(route_bb) if self._ignore_vehicles: - return (False, None, -1) + return ObstacleDetectionResult(False, None, -1) if vehicle_list is None: vehicle_list = self._world.get_actors().filter("*vehicle*") if len(vehicle_list) == 0: - return (False, None, -1) + return ObstacleDetectionResult(False, None, -1) if not max_distance: max_distance = self._base_vehicle_threshold @@ -395,7 +397,7 @@ class BasicAgent(object): target_polygon = Polygon(target_list) if route_polygon.intersects(target_polygon): - return (True, target_vehicle, compute_distance(target_vehicle.get_location(), ego_location)) + return ObstacleDetectionResult(True, target_vehicle, compute_distance(target_vehicle.get_location(), ego_location)) # Simplified approach, using only the plan waypoints (similar to TM) else: @@ -416,9 +418,9 @@ class BasicAgent(object): ) if is_within_distance(target_rear_transform, ego_front_transform, max_distance, [low_angle_th, up_angle_th]): - return (True, target_vehicle, compute_distance(target_transform.location, ego_transform.location)) + return ObstacleDetectionResult(True, target_vehicle, compute_distance(target_transform.location, ego_transform.location)) - return (False, None, -1) + return ObstacleDetectionResult(False, None, -1) def _generate_lane_change_path(self, waypoint, direction='left', distance_same_lane=10, distance_other_lane=25, lane_change_distance=25, diff --git a/PythonAPI/carla/agents/tools/hints.py b/PythonAPI/carla/agents/tools/hints.py new file mode 100644 index 000000000..475d93d3d --- /dev/null +++ b/PythonAPI/carla/agents/tools/hints.py @@ -0,0 +1,34 @@ +""" +Module to add high-level semantic return types for obstacle and traffic light detection results via named tuples. + +The code is compatible with Python 2.7, <3.6 and >=3.6. The later uses the typed version of named tuples. +""" + + +import sys +if sys.version_info < (3, 6): + from collections import namedtuple + ObstacleDetectionResult = namedtuple('ObstacleDetectionResult', ['obstacle_was_found', 'obstacle', 'distance']) + TrafficLightDetectionResult = namedtuple('TrafficLightDetectionResult', ['traffic_light_was_found', 'traffic_light']) +else: + from typing import NamedTuple, Union, TYPE_CHECKING + from carla import Actor, TrafficLight + """ + # Python 3.6+, incompatible with Python 2.7 syntax + class ObstacleDetectionResult(NamedTuple): + obstacle_was_found : bool + obstacle : Union[Actor, None] + distance : float + # distance : Union[float, Literal[-1]] # Python 3.8+ only + + class TrafficLightDetectionResult(NamedTuple): + traffic_light_was_found : bool + traffic_light : Union[TrafficLight, None] + """ + if TYPE_CHECKING: + from typing import Literal + ObstacleDetectionResult = NamedTuple('ObstacleDetectionResult', [('obstacle_was_found', bool), ('obstacle', Union[Actor, None]), ('distance', Union[float, Literal[-1]])]) + else: + ObstacleDetectionResult = NamedTuple('ObstacleDetectionResult', [('obstacle_was_found', bool), ('obstacle', Union[Actor, None]), ('distance', float)]) + + TrafficLightDetectionResult = NamedTuple('TrafficLightDetectionResult', [('traffic_light_was_found', bool), ('traffic_light', Union[TrafficLight, None])]) From 696d11f99533faf045b4b4dafad79d0af646f204 Mon Sep 17 00:00:00 2001 From: Ruben Abad Date: Mon, 3 Jun 2024 13:39:34 +0200 Subject: [PATCH 08/19] test only in gpu nodes --- Jenkinsfile | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Jenkinsfile b/Jenkinsfile index b7352cac9..509b3090b 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -17,7 +17,7 @@ pipeline //{ stage('ubuntu') { - agent { label "gpu" } + agent { label "ubuntu_20_04" } environment { UE4_ROOT = '/home/jenkins/UnrealEngine_4.26' @@ -207,6 +207,7 @@ pipeline { stage('ubuntu smoke tests') { + agent { label "gpu_20_04" } steps { unstash name: 'ubuntu_eggs' From 68ce217d26fb98fdff9d91f1064d850464994a5a Mon Sep 17 00:00:00 2001 From: Ruben Abad Date: Mon, 3 Jun 2024 13:40:18 +0200 Subject: [PATCH 09/19] master and dev branches do documentation upload on main branch --- Jenkinsfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Jenkinsfile b/Jenkinsfile index 509b3090b..b3fd05fef 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -316,7 +316,7 @@ pipeline tar -xvzf carla_doc.tar.gz git add Doxygen git commit -m "Updated c++ docs" || true - git push --set-upstream origin ruben/jenkins_migration + git push --set-upstream origin master ''' } } From 3654f6bb24a0cd6bb9574e1164a481c64ce42337 Mon Sep 17 00:00:00 2001 From: Ruben Abad Date: Mon, 3 Jun 2024 16:06:15 +0200 Subject: [PATCH 10/19] prevent test stages to download repo again --- Jenkinsfile | 1 + 1 file changed, 1 insertion(+) diff --git a/Jenkinsfile b/Jenkinsfile index b3fd05fef..3cae36aa6 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -208,6 +208,7 @@ pipeline stage('ubuntu smoke tests') { agent { label "gpu_20_04" } + options{skipDefaultCheckout()} steps { unstash name: 'ubuntu_eggs' From 6898225f5ddc768af4136df6c142e30259487a00 Mon Sep 17 00:00:00 2001 From: MattRoweEAIF <125647690+MattRoweEAIF@users.noreply.github.com> Date: Tue, 4 Jun 2024 11:56:30 +0200 Subject: [PATCH 11/19] added UE5 build instructions (#7743) --- Docs/build_linux_ue5.md | 91 +++++++++++++++++++++++++++++++++++++++ Docs/build_windows_ue5.md | 79 +++++++++++++++++++++++++++++++++ 2 files changed, 170 insertions(+) create mode 100644 Docs/build_linux_ue5.md create mode 100644 Docs/build_windows_ue5.md diff --git a/Docs/build_linux_ue5.md b/Docs/build_linux_ue5.md new file mode 100644 index 000000000..62a270441 --- /dev/null +++ b/Docs/build_linux_ue5.md @@ -0,0 +1,91 @@ +!!! warning + This is a work in progress!! This version of CARLA is not considered a stable release. Over the following months many significant changes may be made to this branch which could break any modifications you make. We advise you to treat this branch as experimental. + +# Building CARLA in Linux with Unreal Engine 5.3 + +!!! note + This build process is implemented and tested for Ubuntu 22.04. We recommend to use this Ubuntu version. + +## Set up the environment + +This guide details how to build CARLA from source on Linux with Unreal Engine 5.3. + +Clone the `ue5-dev` branch of CARLA on your local machine: + +```sh +git clone -b ue5-dev https://github.com/carla-simulator/carla.git CarlaUE5 +``` + +Run the setup script: + +```sh +cd CarlaUE5 +bash -x Setup.sh +``` + +The Setup.sh script installs all the required packages, including Cmake, debian packages, Python packages and Unreal Engine 5.3. It also downloads the CARLA content and builds CARLA. This script can therefore take a long time to complete. + +!!! note + * This version of CARLA requires the **CARLA fork of Unreal Engine 5.3**. You need to link your GitHub account to Epic Games in order to gain permission to clone the UE repository. If you have not already linked your accounts, follow [this guide](https://www.unrealengine.com/en-US/ue4-on-github) + * For using CARLA Unreal Engine 5 previous builds, **ensure CARLA_UNREAL_ENGINE_PATH environment variable is defined** pointing to the CARLA Unreal Engine 5.3 absolute path. If this variable is not defined, the Setup.sh script will download and build CARLA Unreal Engine 5 and **this takes more than 1 extra hour of build and 225Gb of disk space**. + * The Setup.sh script checks if there is any Python installed at the top of the PATH variable, and installs Python otherwise. **To use your own version of Python, ensure that the PATH variable is properly set for Python before running the script**. + * CARLA cannot be built on an external disk, Ubuntu is not giving the required read/write/execution permissions for builds. + + +## Build and Run CARLA UE5 + +The setup script launches the following commands itself, you will need to use the following commands once you modify the code and wish to relaunch: + +* Configure: + +```sh +cmake -G Ninja -S . -B Build --toolchain=$PWD/CMake/LinuxToolchain.cmake \ +-DLAUNCH_ARGS="-prefernvidia" -DCMAKE_BUILD_TYPE=Release -DENABLE_ROS2=ON \ +-DBUILD_CARLA_UNREAL=ON -DCARLA_UNREAL_ENGINE_PATH=$CARLA_UNREAL_ENGINE_PATH +``` + +* Build CARLA: + +```sh +cmake --build Build +``` + +* Build and install the Python API: + +```sh +cmake --build Build --target carla-python-api-install +``` + +* Launch the editor: + +```sh +cmake --build Build --target launch +``` + +## Build a package with CARLA UE5 + +```sh +cmake --build Build --target package +``` + +The package will be generated in the directory `$CARLA_PATH/Build/Package` + +## Run the package + +Run the package with the following command. + +```sh +./CarlaUnreal.sh +``` + +If you want to run the native ROS2 interface, add the `--ros2` argument + +```sh +./CarlaUnreal.sh --ros2 +``` + +If you want to install the Python API corresponding to the package you have built: + +```sh +pip3 install PythonAPI/carla/dist/carla-*.whl +``` \ No newline at end of file diff --git a/Docs/build_windows_ue5.md b/Docs/build_windows_ue5.md new file mode 100644 index 000000000..70b1eeb9e --- /dev/null +++ b/Docs/build_windows_ue5.md @@ -0,0 +1,79 @@ +!!! warning + This is a work in progress!! This version of CARLA is not considered a stable release. Over the following months many significant changes may be made to this branch which could break any modifications you make. We advise you to treat this branch as experimental. + +# Building CARLA in Windowswith Unreal Engine 5.3 + +## Set up the environment + +This guide details how to build CARLA from source on Windows with Unreal Engine 5.3. + +Clone the `ue5-dev` branch of CARLA on your local machine: + +```sh +git clone -b ue5-dev https://github.com/carla-simulator/carla.git CarlaUE5 +``` + +Run the setup script: + +```sh +cd CarlaUE5 +Setup.bat +``` + +The Setup.bat script installs all the required packages, including Visual Studio 2022, Cmake, Python packages and Unreal Engine 5. It also downloads the CARLA content and builds CARLA. This batch file can therefore take a long time to complete. + +!!! note + * This version of CARLA requires the **CARLA fork of Unreal Engine 5.3**. You need to link your GitHub account to Epic Games in order to gain permission to clone the UE repository. If you have not already linked your accounts, follow [this guide](https://www.unrealengine.com/en-US/ue4-on-github) + * For using CARLA Unreal Engine 5 previous builds, ensure CARLA_UNREAL_ENGINE_PATH environment variable is defined pointing to the CARLA Unreal Engine 5 absolute path. If this variable is not defined, Setup.bat script will download and build CARLA Unreal Engine 5 and **this takes more than 1 extra hour of build and a 225Gb of disk space**. + * Setup.bat script checks if there is any Python version installed at the top of the PATH variable, and installs Python otherwise. **To use your own version of Python, ensure that the PATH variable is properly set for Python before running the script**. + * **Windows Developer Mode should be active**, otherwise build will fail. Please see [here](https://learn.microsoft.com/en-us/gaming/game-bar/guide/developer-mode) for instructions on how to activate Developer Mode. + * **CARLA cannot be built on an external disk**, Windows does not give the required read/write/execution permissions for builds. + + +## Build and Run CARLA UE5 + +The Setup.bat file launches the following commands itself, you will need to use the following commands once you modify the code and wish to relaunch: + +!!! warning + Ensure CARLA_UNREAL_ENGINE_PATH environment variable is defined pointing to the CARLA Unreal Engine 5.3 absolute path. Setup.bat sets this variable, but I may not be set if another approach was followed to install the requirements. + +* **Configure**. Open x64 Native Tools Command Prompt for VS 2022 at the CarlaUE5 folder and runn the following command: + +```sh +cmake -G Ninja -S . -B Build -DCMAKE_BUILD_TYPE=Release -DBUILD_CARLA_UNREAL=ON -DCARLA_UNREAL_ENGINE_PATH=%CARLA_UNREAL_ENGINE_PATH% +``` + +* **Build CARLA**. Open the x64 Native Tools Command Prompt for VS 2022 at the CarlaUE5 folder and run the following command: + +```sh +cmake --build Build +``` + +* **Build and install the Python API**. Open the x64 Native Tools Command Prompt for VS 2022 at the CarlaUE5 folder and run the following command:: + +```sh +cmake --build Build --target carla-python-api-install +``` + +* **Launch the editor**. Open the x64 Native Tools Command Prompt for VS 2022 at the CarlaUE5 folder and run the following command: + +```sh +cmake --build Build --target launch +``` + +## Build a package with CARLA UE5 + +!!! warning + The package build for Carla UE5 is not yet fully tested for Windows. + +Open the x64 Native Tools Command Prompt for VS 2022 at the CarlaUE5 folder and run the following command: + +```sh +cmake --build Build --target package +``` + +The package will be generated in the directory `Build/Package` + +## Run the package + +The package build is not yet tested for Windows From d6078abdbfef8f8d4aab703109212152137d2e37 Mon Sep 17 00:00:00 2001 From: Ruben Abad Date: Tue, 4 Jun 2024 12:12:57 +0200 Subject: [PATCH 12/19] reverting previous change: repo checkout is neccessary to have access to makefile --- Jenkinsfile | 1 - 1 file changed, 1 deletion(-) diff --git a/Jenkinsfile b/Jenkinsfile index 3cae36aa6..b3fd05fef 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -208,7 +208,6 @@ pipeline stage('ubuntu smoke tests') { agent { label "gpu_20_04" } - options{skipDefaultCheckout()} steps { unstash name: 'ubuntu_eggs' From b69f892537766e8135cd80690a150067e0ef51af Mon Sep 17 00:00:00 2001 From: MattRoweEAIF <125647690+MattRoweEAIF@users.noreply.github.com> Date: Tue, 4 Jun 2024 12:28:12 +0200 Subject: [PATCH 13/19] Docs/ue5 instructions (#7747) * added UE5 build instructions * added links in main build doc --- Docs/build_carla.md | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/Docs/build_carla.md b/Docs/build_carla.md index 1ac943002..d0e1fed62 100644 --- a/Docs/build_carla.md +++ b/Docs/build_carla.md @@ -9,7 +9,10 @@ Build instructions are available for Linux and Windows. You can also build CARLA * [__Docker__](build_docker.md) * [__Docker with Unreal__](build_docker_unreal.md) * [__Updating CARLA__](build_update.md) -* [__Build system__](build_system.md) +* [__Build system__](build_system.md) + +* [__Linux build with Unreal Engine 5.3__](build_linux_ue5.md) +* [__Windows build with Unreal Engine 5.3__](build_windows_ue5.md) * [__FAQ__](build_faq.md) From dae1d5821149278dd709e3c852a97ba2a438154a Mon Sep 17 00:00:00 2001 From: Ruben Abad Date: Tue, 4 Jun 2024 15:23:46 +0200 Subject: [PATCH 14/19] update credentials --- Jenkinsfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Jenkinsfile b/Jenkinsfile index b3fd05fef..fb0a2d5e5 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -311,7 +311,7 @@ pipeline dir('doc_repo') { unstash name: 'carla_docs' - withCredentials([gitUsernamePassword(credentialsId: 'github_token_as_pwd_2', gitToolName: 'git-tool')]) { + withCredentials([gitUsernamePassword(credentialsId: 'carla_test_1', gitToolName: 'git-tool')]) { sh ''' tar -xvzf carla_doc.tar.gz git add Doxygen From 5287e239a38a159ba0cd355c4152a8129cd9ef17 Mon Sep 17 00:00:00 2001 From: Ruben Abad Date: Tue, 4 Jun 2024 15:41:49 +0200 Subject: [PATCH 15/19] reverting credentials --- Jenkinsfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Jenkinsfile b/Jenkinsfile index fb0a2d5e5..b3fd05fef 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -311,7 +311,7 @@ pipeline dir('doc_repo') { unstash name: 'carla_docs' - withCredentials([gitUsernamePassword(credentialsId: 'carla_test_1', gitToolName: 'git-tool')]) { + withCredentials([gitUsernamePassword(credentialsId: 'github_token_as_pwd_2', gitToolName: 'git-tool')]) { sh ''' tar -xvzf carla_doc.tar.gz git add Doxygen From e2574609f91f79875bd9152631d6faa077f5d44e Mon Sep 17 00:00:00 2001 From: Ruben Abad Date: Wed, 5 Jun 2024 12:29:36 +0200 Subject: [PATCH 16/19] doucmentation is pulled/pushed to "dev" branch --- Jenkinsfile | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index b3fd05fef..2eb130419 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -132,7 +132,7 @@ pipeline dir('doc_repo') { checkout scmGit( - branches: [[name: '*/master']], + branches: [[name: '*/dev']], extensions: [ cleanBeforeCheckout(), checkoutOption(120), @@ -316,7 +316,7 @@ pipeline tar -xvzf carla_doc.tar.gz git add Doxygen git commit -m "Updated c++ docs" || true - git push --set-upstream origin master + git push --set-upstream origin dev ''' } } From 18035969feedddb1124fbd2152a925c92326f33a Mon Sep 17 00:00:00 2001 From: MattRoweEAIF <125647690+MattRoweEAIF@users.noreply.github.com> Date: Mon, 10 Jun 2024 17:02:53 +0200 Subject: [PATCH 17/19] changed get_required_files docs (#7763) * changed get_required_files docs * fixed overwritten user data --- Docs/python_api.md | 116 +++++++++++++++------------------ PythonAPI/docs/client.yml | 4 +- PythonAPI/docs/sensor.yml | 46 ++++++++----- PythonAPI/docs/sensor_data.yml | 112 ++++++++++++++++++++++++++++++- 4 files changed, 197 insertions(+), 81 deletions(-) diff --git a/Docs/python_api.md b/Docs/python_api.md index e0e0aa72a..a7ab163a2 100644 --- a/Docs/python_api.md +++ b/Docs/python_api.md @@ -421,19 +421,16 @@ Parses the location and extent of the bounding box to string. ## carla.CAMData Inherited from _[carla.SensorData](#carla.SensorData)_
-This is the data type for cooperative awareness message reception, contained in a [CAMEvent](#carlacamevent) +This is the data type for cooperative awareness message reception, contained in a [CAMEvent](#carlacamevent). + ### Instance Variables -- **power** (_float - dBm_) +- **power** (_float - dBm_) Received power. ### Methods -- **get**(**self**) -Get the CAM data. - - **Return:** _dict_ - - Returns a nested dictionary containing the message following the ETSI standard: - - `"Header"`: _dict_ - - `"Message"`: _dict_ +- **get**(**self**) +Get the CAM data. Returns a nested dictionary containing the message following the ETSI standard: - `Header`: dict - `Message`: dict. + - **Return:** _dict_ ##### Dunder methods - **\__str__**(**self**) @@ -442,25 +439,23 @@ Get the CAM data. ## carla.CAMEvent Inherited from _[carla.SensorData](#carla.SensorData)_
-Class that defines the data provided by a sensor.other.v2x. This is a collection type to combine returning several [CAMData](#carlacamdata). - -### Instance Variables - +Class that defines the data provided by a **sensor.other.v2x**. This is a collection type to combine returning several [CAMData](#carlacamdata). ### Methods -- **get_message_count**(**self**) -Get the number of received CAM's. - - **Return:** _int_ + +##### Getters +- **get_message_count**(**self**) +Get the number of received CAM's. + - **Return:** _int_ ##### Dunder methods -- **\__getitem__**(**self**, **pos**=int) +- **\__get_item__**(**self**, **pos**=int) - **\__iter__**(**self**) -Iterate over the [carla.CAMData](#carla.CAMData) retrieved as data. -- **\__len__**(**self**) +Iterate over the [CAMData](#carlacamdata) retrieved as data. +- **\__len__**(**self**) --- - ## carla.CityObjectLabel Enum declaration that contains the different tags available to filter the bounding boxes returned by [carla.World.get_level_bbs](#carla.World.get_level_bbs)(). These values correspond to the [semantic tag](ref_sensors.md#semantic-segmentation-camera) that the elements in the scene have. @@ -618,8 +613,8 @@ Returns the client libcarla version by consulting it in the "Version.h" file. Bo - **get_required_files**(**self**, **folder**, **download**=True) Asks the server which files are required by the client to use the current map. Option to download files automatically if they are not already in the cache. - **Parameters:** - - `folder` (_str_) - Folder where files required by the client will be downloaded to. - - `download` (_bool_) - If True, downloads files that are not already in cache. + - `folder` (_str_) - Specifies a folder to look through on the server maps. Leaving this blank will search recursively through all map folders in the server, which is recommended if you're unfamiliar with the server map folder structure. + - `download` (_bool_) - If True, downloads files that are not already in cache. The cache can be found at "HOME\carlaCache" or "USERPROFILE\carlaCache", depending on OS. - **get_server_version**(**self**) Returns the server libcarla version by consulting it in the "Version.h" file. Both client and server should use the same libcarla version. - **Return:** _str_ @@ -710,23 +705,19 @@ Converts the image to a depth map using a logarithmic scale, leading to better p No changes applied to the image. Used by the [RGB camera](ref_sensors.md#rgb-camera). --- + ## carla.CustomV2XData Inherited from _[carla.SensorData](#carla.SensorData)_
-This is the data type defining a custom V2X message. Received as part of a [CustomV2XEvent](#carla.CustomV2XEvent). +This is the data type defining a custom V2X message. Received as part of a [CustomV2XEvent](#carlacustomv2xevent). ### Instance Variables -- **power** (_float - dBm_) +- **power** (_float - dBm_) Received power. ### Methods -- **get**(**self**) -Get the custom message. - - **Return:** _dict_. - - Returns a nested dictionary containing the message. It has two primary keys: - - `"Header"` : _dict_ - - `"Message"`: _str_ - +- **get**(**self**) +Get the custom message. Returns a nested dictionary containing the message. It has two primary keys: - `Header` : dict - `Message`: str. + - **Return:** _dict_ ##### Dunder methods - **\__str__**(**self**) @@ -735,25 +726,23 @@ Get the custom message. ## carla.CustomV2XEvent Inherited from _[carla.SensorData](#carla.SensorData)_
-Class that defines the data provided by a sensor.other.v2x_custom. This is a collection type to combine returning several [CustomV2XData](#carla.CustomV2XData). - -### Instance Variables - +Class that defines the data provided by a **sensor.other.v2x_custom**. This is a collection type to combine returning several [CustomV2XData](#carlacustomv2xdata). ### Methods -- **get_message_count**(**self**) -Get the number of received CAM's. - - **Return:** _int_ + +##### Getters +- **get_message_count**(**self**) +Get the number of received CAM's. + - **Return:** _int_ ##### Dunder methods -- **\__getitem__**(**self**, **pos**=int) +- **\__get_item__**(**self**, **pos**=int) - **\__iter__**(**self**) -Iterate over the [carla.CustomV2XData](#carla.CustomV2XData) retrieved as data. +Iterate over the [CustomV2XData](#carlacustomv2xdata) retrieved as data. - **\__len__**(**self**) --- - ## carla.DVSEvent Class that defines a DVS event. An event is a quadruple, so a tuple of 4 elements, with `x`, `y` pixel coordinate location, timestamp `t` and polarity `pol` of the event. Learn more about them [here](ref_sensors.md). @@ -942,7 +931,7 @@ Initializes a color, black by default. --- ## carla.GBufferTextureID -Defines the identifiers of each GBuffer texture (See the method `[carla.Sensor.listen_to_gbuffer](#carla.Sensor.listen_to_gbuffer)`). +Defines the of each GBuffer texture (See the method `[carla.Sensor.listen_to_gbuffer](#carla.Sensor.listen_to_gbuffer)`). ### Instance Variables - **SceneColor** @@ -2315,26 +2304,26 @@ Iterate over the [carla.SemanticLidarDetection](#carla.SemanticLidarDetection) r Inherited from _[carla.Actor](#carla.Actor)_
Sensors compound a specific family of actors quite diverse and unique. They are normally spawned as attachment/sons of a vehicle (take a look at [carla.World](#carla.World) to learn about actor spawning). Sensors are thoroughly designed to retrieve different types of data that they are listening to. The data they receive is shaped as different subclasses inherited from [carla.SensorData](#carla.SensorData) (depending on the sensor). - Most sensors can be divided in two groups: those receiving data on every tick (cameras, point clouds and some specific sensors) and those who only receive under certain circumstances (trigger detectors). CARLA provides a specific set of sensors and their blueprint can be found in [carla.BlueprintLibrary](#carla.BlueprintLibrary). All the information on their preferences and settlement can be found [here](ref_sensors.md), but the list of those available in CARLA so far goes as follow. -
Receive data on every tick. - - [Depth camera](ref_sensors.md#depth-camera). - - [Gnss sensor](ref_sensors.md#gnss-sensor). - - [IMU sensor](ref_sensors.md#imu-sensor). - - [Lidar raycast](ref_sensors.md#lidar-raycast-sensor). - - [SemanticLidar raycast](ref_sensors.md#semanticlidar-raycast-sensor). - - [Radar](ref_sensors.md#radar-sensor). - - [RGB camera](ref_sensors.md#rgb-camera). - - [RSS sensor](ref_sensors.md#rss-sensor). - - [Semantic Segmentation camera](ref_sensors.md#semantic-segmentation-camera). -
Only receive data when triggered. - - [Collision detector](ref_sensors.md#collision-detector). - - [Lane invasion detector](ref_sensors.md#lane-invasion-detector). - - [Obstacle detector](ref_sensors.md#obstacle-detector). + Most sensors can be divided in two groups: those receiving data on every tick (cameras, point clouds and some specific sensors) and those who only receive under certain circumstances (trigger detectors). CARLA provides a specific set of sensors and their blueprint can be found in [carla.BlueprintLibrary](#carla.BlueprintLibrary). All the information on their preferences and settlement can be found [here](ref_sensors.md), but the list of those available in CARLA so far goes as follows:
+
Receive data on every tick
+ - [Depth camera](ref_sensors.md#depth-camera)
+ - [Gnss sensor](ref_sensors.md#gnss-sensor)
+ - [IMU sensor](ref_sensors.md#imu-sensor)
+ - [Lidar raycast](ref_sensors.md#lidar-raycast-sensor)
+ - [SemanticLidar raycast](ref_sensors.md#semanticlidar-raycast-sensor)
+ - [Radar](ref_sensors.md#radar-sensor)
+ - [RGB camera](ref_sensors.md#rgb-camera)
+ - [RSS sensor](ref_sensors.md#rss-sensor)
+ - [Semantic Segmentation camera](ref_sensors.md#semantic-segmentation-camera)
+
Only receive data when triggered.
+ - [Collision detector](ref_sensors.md#collision-detector)
+ - [Lane invasion detector](ref_sensors.md#lane-invasion-detector)
+ - [Obstacle detector](ref_sensors.md#obstacle-detector)
- [V2X sensor](ref_sensors.md#v2x-sensor). ### Instance Variables - **is_listening** (_boolean_) -When True the sensor will be waiting for data. +When **True** the sensor will be waiting for data. ### Methods - **disable_for_ros**(**self**) @@ -2343,12 +2332,15 @@ Commands the sensor to not be processed for publishing in ROS2 if there is no an Commands the sensor to be processed to be able to publish in ROS2 without any listen to it. - **is_enabled_for_ros**(**self**) Returns if the sensor is enabled or not to publish in ROS2 if there is no any listen to it. + - **Return:** _bool_ - **is_listening**(**self**) Returns whether the sensor is in a listening state. + - **Return:** _bool_ - **is_listening_gbuffer**(**self**, **gbuffer_id**) Returns whether the sensor is in a listening state for a specific GBuffer texture. - **Parameters:** - `gbuffer_id` (_[carla.GBufferTextureID](#carla.GBufferTextureID)_) - The ID of the target Unreal Engine GBuffer texture. + - **Return:** _bool_ - **listen**(**self**, **callback**) The function the sensor will be calling to every time a new measurement is received. This function needs for an argument containing an object type [carla.SensorData](#carla.SensorData) to work with. - **Parameters:** @@ -2361,7 +2353,7 @@ The function the sensor will be calling to every time the desired GBuffer textur - **send**(**self**, **message**) Instructs the sensor to send the string given by `message` to all other CustomV2XSensors on the next tick. - **Parameters:** - - `message` (_string_) - The data to send. *Note*: maximum string length is 100 chars. + - `message` (_string_) - The data to send. Note: maximum string length is 100 chars. - **stop**(**self**) Commands the sensor to stop listening for data. - **stop_gbuffer**(**self**, **gbuffer_id**) @@ -2385,8 +2377,8 @@ Base class for all the objects containing data generated by a [carla.Sensor](#ca - Obstacle detector: [carla.ObstacleDetectionEvent](#carla.ObstacleDetectionEvent).
- Radar sensor: [carla.RadarMeasurement](#carla.RadarMeasurement).
- RSS sensor: [carla.RssResponse](#carla.RssResponse).
- - Semantic LIDAR sensor: [carla.SemanticLidarMeasurement](#carla.SemanticLidarMeasurement). - - Cooperative awareness messages V2X sensor: [carla.CAMEvent](#carla.CAMEvent). + - Semantic LIDAR sensor: [carla.SemanticLidarMeasurement](#carla.SemanticLidarMeasurement).
+ - Cooperative awareness messages V2X sensor: [carla.CAMEvent](#carla.CAMEvent).
- Custom V2X messages V2X sensor: [carla.CustomV2XEvent](#carla.CustomV2XEvent). ### Instance Variables diff --git a/PythonAPI/docs/client.yml b/PythonAPI/docs/client.yml index 3f4e40388..2977c9337 100644 --- a/PythonAPI/docs/client.yml +++ b/PythonAPI/docs/client.yml @@ -352,12 +352,12 @@ - param_name: folder type: str doc: > - Folder where files required by the client will be downloaded to. + Specifies a folder to look through on the server maps. Leaving this blank will search recursively through all map folders in the server, which is recommended if you're unfamiliar with the server map folder structure. - param_name: download type: bool default: True doc: > - If True, downloads files that are not already in cache. + If True, downloads files that are not already in cache. The cache can be found at "HOME\carlaCache" or "USERPROFILE\carlaCache", depending on OS. doc: > Asks the server which files are required by the client to use the current map. Option to download files automatically if they are not already in the cache. # -------------------------------------- diff --git a/PythonAPI/docs/sensor.yml b/PythonAPI/docs/sensor.yml index 06e78c2a5..5885217cd 100644 --- a/PythonAPI/docs/sensor.yml +++ b/PythonAPI/docs/sensor.yml @@ -8,21 +8,28 @@ doc: > Sensors compound a specific family of actors quite diverse and unique. They are normally spawned as attachment/sons of a vehicle (take a look at carla.World to learn about actor spawning). Sensors are thoroughly designed to retrieve different types of data that they are listening to. The data they receive is shaped as different subclasses inherited from carla.SensorData (depending on the sensor). - Most sensors can be divided in two groups: those receiving data on every tick (cameras, point clouds and some specific sensors) and those who only receive under certain circumstances (trigger detectors). CARLA provides a specific set of sensors and their blueprint can be found in carla.BlueprintLibrary. All the information on their preferences and settlement can be found [here](ref_sensors.md), but the list of those available in CARLA so far goes as follow. -
Receive data on every tick. - - [Depth camera](ref_sensors.md#depth-camera). - - [Gnss sensor](ref_sensors.md#gnss-sensor). - - [IMU sensor](ref_sensors.md#imu-sensor). - - [Lidar raycast](ref_sensors.md#lidar-raycast-sensor). - - [SemanticLidar raycast](ref_sensors.md#semanticlidar-raycast-sensor). - - [Radar](ref_sensors.md#radar-sensor). - - [RGB camera](ref_sensors.md#rgb-camera). - - [RSS sensor](ref_sensors.md#rss-sensor). - - [Semantic Segmentation camera](ref_sensors.md#semantic-segmentation-camera). -
Only receive data when triggered. - - [Collision detector](ref_sensors.md#collision-detector). - - [Lane invasion detector](ref_sensors.md#lane-invasion-detector). - - [Obstacle detector](ref_sensors.md#obstacle-detector). + Most sensors can be divided in two groups: those receiving data on every tick (cameras, point clouds and some specific sensors) and those who only receive under certain circumstances (trigger detectors). CARLA provides a specific set of sensors and their blueprint can be found in carla.BlueprintLibrary. All the information on their preferences and settlement can be found [here](ref_sensors.md), but the list of those available in CARLA so far goes as follows:
+
Receive data on every tick
+ - [Depth camera](ref_sensors.md#depth-camera)
+ - [Gnss sensor](ref_sensors.md#gnss-sensor)
+ - [IMU sensor](ref_sensors.md#imu-sensor)
+ - [Lidar raycast](ref_sensors.md#lidar-raycast-sensor)
+ - [SemanticLidar raycast](ref_sensors.md#semanticlidar-raycast-sensor)
+ - [Radar](ref_sensors.md#radar-sensor)
+ - [RGB camera](ref_sensors.md#rgb-camera)
+ - [RSS sensor](ref_sensors.md#rss-sensor)
+ - [Semantic Segmentation camera](ref_sensors.md#semantic-segmentation-camera)
+
Only receive data when triggered.
+ - [Collision detector](ref_sensors.md#collision-detector)
+ - [Lane invasion detector](ref_sensors.md#lane-invasion-detector)
+ - [Obstacle detector](ref_sensors.md#obstacle-detector)
+ - [V2X sensor](ref_sensors.md#v2x-sensor) + # - PROPERTIES ------------------------- + instance_variables: + - var_name: is_listening + type: boolean + doc: > + When **True** the sensor will be waiting for data. # - METHODS ---------------------------- methods: - def_name: listen @@ -92,6 +99,15 @@ doc: > Commands the sensor to stop listening for the specified GBuffer texture. # -------------------------------------- + - def_name: send + params: + - param_name: message + type: string + doc: > + The data to send. Note: maximum string length is 100 chars. + doc: > + Instructs the sensor to send the string given by `message` to all other CustomV2XSensors on the next tick. + # -------------------------------------- - def_name: __str__ # -------------------------------------- diff --git a/PythonAPI/docs/sensor_data.yml b/PythonAPI/docs/sensor_data.yml index 1e0e477e1..cdd394a56 100644 --- a/PythonAPI/docs/sensor_data.yml +++ b/PythonAPI/docs/sensor_data.yml @@ -15,7 +15,9 @@ - Obstacle detector: carla.ObstacleDetectionEvent.
- Radar sensor: carla.RadarMeasurement.
- RSS sensor: carla.RssResponse.
- - Semantic LIDAR sensor: carla.SemanticLidarMeasurement. + - Semantic LIDAR sensor: carla.SemanticLidarMeasurement.
+ - Cooperative awareness messages V2X sensor: carla.CAMEvent.
+ - Custom V2X messages V2X sensor: carla.CustomV2XEvent. # - PROPERTIES ------------------------- instance_variables: - var_name: frame @@ -878,7 +880,7 @@ - class_name: GBufferTextureID # - DESCRIPTION ------------------------ doc: > - Defines the identifiers of each GBuffer texture (See the method `carla.Sensor.listen_to_gbuffer`). + Defines the of each GBuffer texture (See the method `carla.Sensor.listen_to_gbuffer`). # - PROPERTIES ------------------------- instance_variables: - var_name: SceneColor @@ -941,4 +943,110 @@ The texture "CustomStencil" contains the Unreal Engine custom stencil data. # -------------------------------------- + + - class_name: CAMData + parent: carla.SensorData + # - DESCRIPTION ------------------------ + doc: > + This is the data type for cooperative awareness message reception, contained in a [CAMEvent](#carlacamevent) + # - PROPERTIES ------------------------- + instance_variables: + - var_name: power + type: float - dBm + doc: > + Received power. + + # - METHODS ---------------------------- + # -------------------------------------- + methods: + - def_name: get + return: dict + doc: > + Get the CAM data. Returns a nested dictionary containing the message following the ETSI standard: - `Header`: dict - `Message`: dict + # -------------------------------------- + - def_name: __str__ + # -------------------------------------- + + - class_name: CAMEvent + parent: carla.SensorData + # - DESCRIPTION ------------------------ + doc: > + Class that defines the data provided by a **sensor.other.v2x**. This is a collection type to combine returning several [CAMData](#carlacamdata). + # - PROPERTIES ------------------------- + instance_variables: + + # - METHODS ---------------------------- + # -------------------------------------- + methods: + - def_name: get_message_count + return: int + doc: > + Get the number of received CAM's. + # -------------------------------------- + - def_name: __get_item__ + params: + - param_name: pos + type: int + # -------------------------------------- + - def_name: __iter__ + doc: > + Iterate over the [CAMData](#carlacamdata) retrieved as data. + # -------------------------------------- + - def_name: __len__ + # -------------------------------------- + + + - class_name: CustomV2XEvent + parent: carla.SensorData + # - DESCRIPTION ------------------------ + doc: > + Class that defines the data provided by a **sensor.other.v2x_custom**. This is a collection type to combine returning several [CustomV2XData](#carlacustomv2xdata). + # - PROPERTIES ------------------------- + instance_variables: + + # - METHODS ---------------------------- + # -------------------------------------- + methods: + - def_name: get_message_count + return: int + doc: > + Get the number of received CAM's. + # -------------------------------------- + - def_name: __get_item__ + params: + - param_name: pos + type: int + # -------------------------------------- + - def_name: __iter__ + doc: > + Iterate over the [CustomV2XData](#carlacustomv2xdata) retrieved as data. + # -------------------------------------- + - def_name: __len__ + # -------------------------------------- + + + - class_name: CustomV2XData + parent: carla.SensorData + # - DESCRIPTION ------------------------ + doc: > + This is the data type defining a custom V2X message. Received as part of a [CustomV2XEvent](#carlacustomv2xevent). + # - PROPERTIES ------------------------- + instance_variables: + - var_name: power + type: float - dBm + doc: > + Received power. + + # - METHODS ---------------------------- + # -------------------------------------- + methods: + - def_name: get + return: dict + doc: > + Get the custom message. Returns a nested dictionary containing the message. It has two primary keys: - `Header` : dict - `Message`: str + # -------------------------------------- + - def_name: __str__ + # -------------------------------------- + + ... From ec7d8fd0379af782a3e953035044feed8f7c4071 Mon Sep 17 00:00:00 2001 From: evilzs1 <152964022+evilzs1@users.noreply.github.com> Date: Tue, 18 Jun 2024 18:04:40 +0800 Subject: [PATCH 18/19] Fixed fate error about number of wheels (#7800) --- .../Source/Carla/Recorder/CarlaRecorderAnimVehicleWheels.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaRecorderAnimVehicleWheels.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaRecorderAnimVehicleWheels.cpp index a79162061..4cb890ca5 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaRecorderAnimVehicleWheels.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaRecorderAnimVehicleWheels.cpp @@ -37,12 +37,12 @@ void CarlaRecorderAnimWheels::Read(std::istream &InFile) ReadValue(InFile, DatabaseId); uint32_t NumWheels = 0; ReadValue(InFile, NumWheels); - WheelValues.reserve(NumWheels); + WheelValues.resize(NumWheels); for (size_t i = 0; i < NumWheels; ++i) { WheelInfo Wheel; Wheel.Read(InFile); - WheelValues.push_back(Wheel); + WheelValues[i] = Wheel; } } From 4da0c7415499981f29874b899edd00c1368df06f Mon Sep 17 00:00:00 2001 From: Daniel Date: Fri, 14 Jun 2024 17:39:30 +0200 Subject: [PATCH 19/19] Rework of BasicAgent's set_destination. Covers the 4 cases start_location=[None (default)/ not None] clean_queue = [True (default), False) --- .../carla/agents/navigation/basic_agent.py | 31 ++++++++++++------- 1 file changed, 19 insertions(+), 12 deletions(-) diff --git a/PythonAPI/carla/agents/navigation/basic_agent.py b/PythonAPI/carla/agents/navigation/basic_agent.py index aeddc005e..2d0b9b91a 100644 --- a/PythonAPI/carla/agents/navigation/basic_agent.py +++ b/PythonAPI/carla/agents/navigation/basic_agent.py @@ -139,30 +139,37 @@ class BasicAgent(object): def get_global_planner(self): """Get method for protected member local planner""" return self._global_planner - - def set_destination(self, end_location, start_location=None): + + def set_destination(self, end_location, start_location=None, clean_queue=True): + # type: (carla.Location, carla.Location | None, bool) -> None """ This method creates a list of waypoints between a starting and ending location, based on the route returned by the global router, and adds it to the local planner. - If no starting location is passed, the vehicle local planner's target location is chosen, - which corresponds (by default), to a location about 5 meters in front of the vehicle. + If no starting location is passed and `clean_queue` is True, the vehicle local planner's + target location is chosen, which corresponds (by default), to a location about 5 meters + in front of the vehicle. + If `clean_queue` is False the newly planned route will be appended to the current route. :param end_location (carla.Location): final location of the route :param start_location (carla.Location): starting location of the route + :param clean_queue (bool): Whether to clear or append to the currently planned route """ if not start_location: - start_location = self._local_planner.target_waypoint.transform.location - clean_queue = True - else: - start_location = self._vehicle.get_location() - clean_queue = False - + if clean_queue and self._local_planner.target_waypoint: + # Plan from the waypoint in front of the vehicle onwards + start_location = self._local_planner.target_waypoint.transform.location + elif not clean_queue and self._local_planner._waypoints_queue: + # Append to the current plan + start_location = self._local_planner._waypoints_queue[-1][0].transform.location + else: + # no target_waypoint or _waypoints_queue empty, use vehicle location + start_location = self._vehicle.get_location() start_waypoint = self._map.get_waypoint(start_location) end_waypoint = self._map.get_waypoint(end_location) - + route_trace = self.trace_route(start_waypoint, end_waypoint) self._local_planner.set_global_plan(route_trace, clean_queue=clean_queue) - + def set_global_plan(self, plan, stop_waypoint_creation=True, clean_queue=True): """ Adds a specific plan to the agent.