Skip to content

Commit

Permalink
Instance segmentation (#8334)
Browse files Browse the repository at this point in the history
* added cpp client build docs (#7942)

* fixed IMU units (#7960)

* Update README.md with new TinyURL links (#7988)

* Added inverse transform (#7999)

Co-authored-by: glopezdiest <glopez@cvc.uab.cat>

* Aaron/fixwheelchair (#8001)

* Fix OSM2ODR build

* Updated fix wheelchair default value

* Docs/unit updates (#8007)

* fixed IMU units

* updated autitwheel version

* Add a `*.pyi` file for auto-completion & hints.

To enable auto-completion and hints in code editors such as VScode, create a `*.pyi` file. This feature is compatible with `python 3.9` and later versions.

* Fixes and missing Iterators

* Fixed Actor.parent

Can be None or an Actor

* Fixed missing return types

* Updated changelog

needs merge with dev version

* Added DSVEventArray iterator

* Added missing type for Labelled Point

* Fixed spelling misstakes

* Removed wrong unit indication

* Added missing -> World to load_world

* Added missing return value to reload_world

* FIX: __init__ methods do not return

* FIX: added ApplyTransform, fixed ApplyTorque

* Filled in missing information and types.

* ActorList.filter actually returns ActorList

* Fixed CityObjectLabels

* Disambiguated get_waypoint signature

Syntax fix (squased)

* Added undocumented variables

FutureActor
laod_world_if_different

* Corrected Sensor.is_listening

Was changed to a function in 0.9.15. More info see: #7439

* Added type hints for `values` attribute on enums

* Fix intendation shadowing methods

* Fix missing @Property

* Formatted some docstring to be shorter

* Added stubs for HUD drawing

Functions from #7168

* Corrected and more precise type-hints

- fixed carla.Waypoint.next_until_lane_end

* Improved get_waypoint disambiguation

correctly added two overload function

* Fix spelling mistakes

* Better usage of Enum if typing.Self is availiable

Using Self will not report an override / incompatible error.

* Fix: Enum values were tuples. Added Flag or Int to Enums

* Fixes for wrong stubs

- OpendriveGenerationParameter had no init
- missing @Property
- wrong signatures

* Added self parameter to property signatures

* Various fixes

- wrong signatures
- wrong names

* Added setters for VehicleControl

* Improved get_waypoints and Literal type hints

* Corrected [try_]spawn_actor keyword name

* Added Transform.inverse_transform and corrected signature

parameter is called in_point not in_vector

* Improved Callable and callbacks signature

* Corrections and additions

more setters
missing, wrong types corrected
spelling

* Fixed Vector arithmetic

* added digital twins video (#8090)

* use actor ids for instance segmentation

* synchronize bboxes between server and client

* add actor_id attribute to bounding boxes

* navigation information is now loaded when changing maps

* Porting the changes done to UE5 to fix the recording leak to UE4

The slowdown is considerably more noticeable here since the engine runs much smoother. This makes evident that this is a stopgap measure, and should be looked into further down the line.

* Fixed typo in CityScapes palette (#8137)

* Correcting makefile typo to avoid override warning for target "downloadplugins" (#8167)

The downloadplugins target is already defined below (line 162).

* fix typo in title (#8225)

* added unreal coord system, fixed v2x (#8251)

---------


Co-authored-by: Minokori <73998474+Minokori@users.noreply.github.com>
Co-authored-by: Daniel <github.blurry@9ox.net>
Co-authored-by: Sergio Paniego Blanco <sergiopaniegoblanco@gmail.com>
Co-authored-by: Ylmdrin <150919430+Ylmdrin@users.noreply.github.com>
  • Loading branch information
5 people authored Nov 5, 2024
1 parent b60034b commit e8947a4
Show file tree
Hide file tree
Showing 20 changed files with 125 additions and 30 deletions.
4 changes: 3 additions & 1 deletion CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,9 @@
* Added named tuples for BasicAgent.py's detection result to allow for type-hints and better semantics.
* Added type-hint support for the PythonAPI
* Added type-hints to GlobalRoutePlanner and use carla.Vector3D code instead of pre 0.9.13 numpy code.

* If available, use ActorIDs instead of Unreal Engine IDs for instance segmentation
* Synchronized actor BoundingBox between server and client
* Add actor_id to bounding boxes

## CARLA 0.9.15

Expand Down
1 change: 0 additions & 1 deletion Docs/adv_cpp_client.md
Original file line number Diff line number Diff line change
Expand Up @@ -138,4 +138,3 @@ TOOLCHAIN=$(CURDIR)/ToolChain.cmake




4 changes: 4 additions & 0 deletions LibCarla/source/carla/client/Actor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,10 @@ namespace client {
return GetEpisode().Lock()->GetActorAcceleration(*this);
}

geom::BoundingBox Actor::GetBoundingBox() const {
return GetEpisode().Lock()->GetActorBoundingBox(*this);
}

geom::Transform Actor::GetComponentWorldTransform(const std::string componentName) const {
return GetEpisode().Lock()->GetActorComponentWorldTransform(*this, componentName);
}
Expand Down
3 changes: 2 additions & 1 deletion LibCarla/source/carla/client/Actor.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,6 @@ namespace client {
: LIBCARLA_INITIALIZE_LIFETIME_PROFILER(init.GetDisplayId()),
Super(std::move(init)) {}

using ActorState::GetBoundingBox;

virtual ~Actor() = default;

Expand Down Expand Up @@ -60,6 +59,8 @@ namespace client {
/// acceleration calculated after the actor's velocity.
geom::Vector3D GetAcceleration() const;

geom::BoundingBox GetBoundingBox() const;

geom::Transform GetComponentWorldTransform(const std::string componentName) const;

geom::Transform GetComponentRelativeTransform(const std::string componentName) const;
Expand Down
4 changes: 4 additions & 0 deletions LibCarla/source/carla/client/detail/Client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -418,6 +418,10 @@ namespace detail {
_pimpl->AsyncCall("add_actor_torque", actor, vector);
}

geom::BoundingBox Client::GetActorBoundingBox(rpc::ActorId actor) {
return _pimpl->CallAndWait<geom::BoundingBox>("get_actor_bounding_box", actor);
}

geom::Transform Client::GetActorComponentWorldTransform(rpc::ActorId actor, const std::string componentName) {
return _pimpl->CallAndWait<geom::Transform>("get_actor_component_world_transform", actor, componentName);
}
Expand Down
3 changes: 3 additions & 0 deletions LibCarla/source/carla/client/detail/Client.h
Original file line number Diff line number Diff line change
Expand Up @@ -238,6 +238,9 @@ namespace detail {
rpc::ActorId actor,
const geom::Vector3D &vector);

geom::BoundingBox GetActorBoundingBox(
rpc::ActorId actor);

geom::Transform GetActorComponentWorldTransform(
rpc::ActorId actor,
const std::string componentName);
Expand Down
4 changes: 4 additions & 0 deletions LibCarla/source/carla/client/detail/Simulator.h
Original file line number Diff line number Diff line change
Expand Up @@ -447,6 +447,10 @@ namespace detail {
return GetActorSnapshot(actor).acceleration;
}

geom::BoundingBox GetActorBoundingBox(const Actor &actor) {
return _client.GetActorBoundingBox(actor.GetId());
}

geom::Transform GetActorComponentWorldTransform(const Actor &actor, const std::string componentName) {
return _client.GetActorComponentWorldTransform(actor.GetId(), componentName);
}
Expand Down
12 changes: 10 additions & 2 deletions LibCarla/source/carla/geom/BoundingBox.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,12 @@ namespace geom {
// -- Constructors ---------------------------------------------------------
// =========================================================================

explicit BoundingBox(const Location &in_location, const Vector3D &in_extent, const Rotation &in_rotation, const uint32_t &in_actor_id)
: location(in_location),
extent(in_extent),
rotation(in_rotation),
actor_id(in_actor_id) {}

explicit BoundingBox(const Location &in_location, const Vector3D &in_extent, const Rotation &in_rotation)
: location(in_location),
extent(in_extent),
Expand All @@ -50,6 +56,7 @@ namespace geom {
Location location; ///< Center of the BoundingBox in local space
Vector3D extent; ///< Half the size of the BoundingBox in local space
Rotation rotation; ///< Rotation of the BoundingBox in local space
uint32_t actor_id;

// =========================================================================
// -- Other methods --------------------------------------------------------
Expand Down Expand Up @@ -137,11 +144,12 @@ namespace geom {
BoundingBox(const FBoundingBox &Box)
: location(Box.Origin),
extent(1e-2f * Box.Extent.X, 1e-2f * Box.Extent.Y, 1e-2f * Box.Extent.Z),
rotation(Box.Rotation) {}
rotation(Box.Rotation),
actor_id(Box.ActorId) {}

#endif // LIBCARLA_INCLUDED_FROM_UE4

MSGPACK_DEFINE_ARRAY(location, extent, rotation);
MSGPACK_DEFINE_ARRAY(location, extent, rotation, actor_id);
};

} // namespace geom
Expand Down
17 changes: 17 additions & 0 deletions LibCarla/source/carla/rpc/BoundingBox.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
// Copyright (c) 2019 Computer Vision Center (CVC) at the Universitat Autonoma
// de Barcelona (UAB).
//
// This work is licensed under the terms of the MIT license.
// For a copy, see <https://opensource.org/licenses/MIT>.

#pragma once

#include "carla/geom/BoundingBox.h"

namespace carla {
namespace rpc {

using BoundingBox = geom::BoundingBox;

} // namespace rpc
} // namespace carla
1 change: 1 addition & 0 deletions PythonAPI/carla/source/libcarla/Geom.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -266,6 +266,7 @@ void export_geom() {
.def_readwrite("location", &cg::BoundingBox::location)
.def_readwrite("extent", &cg::BoundingBox::extent)
.def_readwrite("rotation", &cg::BoundingBox::rotation)
.def_readonly("actor_id", &cg::BoundingBox::actor_id)
.def("contains", &cg::BoundingBox::Contains, arg("point"), arg("bbox_transform"))
.def("get_local_vertices", CALL_RETURNING_LIST(cg::BoundingBox, GetLocalVertices))
.def("get_world_vertices", CALL_RETURNING_LIST_1(cg::BoundingBox, GetWorldVertices, const cg::Transform&), arg("bbox_transform"))
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ TPair<EActorSpawnResultStatus, FCarlaActor*> UActorDispatcher::SpawnActor(
}
else
{
ATagger::TagActor(*View->GetActor(), true);
ATagger::TagActor(*View->GetActor(), true, View->GetActorId());
}

return MakeTuple(Result.Status, View);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -184,11 +184,6 @@ void ACarlaGameModeBase::BeginPlay()
LoadMapLayer(GameInstance->GetCurrentMapLayer());
ReadyToRegisterObjects = true;

if (true) { /// @todo If semantic segmentation enabled.
ATagger::TagActorsInLevel(*World, true);
TaggerDelegate->SetSemanticSegmentationEnabled();
}

// HACK: fix transparency see-through issues
// The problem: transparent objects are visible through walls.
// This is due to a weird interaction between the SkyAtmosphere component,
Expand All @@ -205,6 +200,11 @@ void ACarlaGameModeBase::BeginPlay()
Episode->InitializeAtBeginPlay();
GameInstance->NotifyBeginEpisode(*Episode);

if (true) { /// @todo If semantic segmentation enabled.
ATagger::TagActorsInLevel(*World, *Episode, true);
TaggerDelegate->SetSemanticSegmentationEnabled();
}

if (Episode->Weather != nullptr)
{
Episode->Weather->ApplyWeather(carla::rpc::WeatherParameters::Default);
Expand Down Expand Up @@ -630,10 +630,10 @@ TArray<FBoundingBox> ACarlaGameModeBase::GetAllBBsOfLevel(uint8 TagQueried) cons
UGameplayStatics::GetAllActorsOfClass(World, AActor::StaticClass(), FoundActors);

TArray<FBoundingBox> BoundingBoxes;
BoundingBoxes = UBoundingBoxCalculator::GetBoundingBoxOfActors(FoundActors, TagQueried);
BoundingBoxes = UBoundingBoxCalculator::GetBoundingBoxOfActors(FoundActors, &GetCarlaEpisode(), TagQueried);

return BoundingBoxes;
}
}

void ACarlaGameModeBase::RegisterEnvironmentObjects()
{
Expand Down Expand Up @@ -773,7 +773,7 @@ void ACarlaGameModeBase::OnLoadStreamLevel()
if(ReadyToRegisterObjects && PendingLevelsToLoad == 0)
{
RegisterEnvironmentObjects();
ATagger::TagActorsInLevel(*GetWorld(), true);
ATagger::TagActorsInLevel(*GetWorld(), *Episode, true);
}
}

Expand Down
40 changes: 29 additions & 11 deletions Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/Tagger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,8 @@
#include "Tagger.h"
#include "TaggedComponent.h"
#include "Vehicle/CarlaWheeledVehicle.h"
#include "Carla/Game/CarlaEpisode.h"
#include "Carla/Actor/CarlaActor.h"

#include "Components/SkeletalMeshComponent.h"
#include "Components/StaticMeshComponent.h"
Expand Down Expand Up @@ -80,17 +82,16 @@ bool ATagger::IsThing(const crp::CityObjectLabel &Label)
Label == crp::CityObjectLabel::TrafficLight);
}

FLinearColor ATagger::GetActorLabelColor(const AActor &Actor, const crp::CityObjectLabel &Label)
FLinearColor ATagger::GetLabelColor(const uint32_t ActorID, const crp::CityObjectLabel &Label)
{
uint32 id = Actor.GetUniqueID();
// TODO: Warn if id > 0xffff.

// Encode label and id like semantic segmentation does
// TODO: Steal bits from R channel and maybe A channel?
FLinearColor Color(0.0f, 0.0f, 0.0f, 1.0f);
Color.R = CastEnum(Label) / 255.0f;
Color.G = ((id & 0x00ff) >> 0) / 255.0f;
Color.B = ((id & 0xff00) >> 8) / 255.0f;
Color.G = ((ActorID & 0x000000ff) >> 0) / 255.0f;
Color.B = ((ActorID & 0x0000ff00) >> 8) / 255.0f;

return Color;
}
Expand All @@ -100,10 +101,10 @@ FLinearColor ATagger::GetActorLabelColor(const AActor &Actor, const crp::CityObj
// -- static ATagger functions -------------------------------------------------
// =============================================================================

void ATagger::TagActor(const AActor &Actor, bool bTagForSemanticSegmentation)
void ATagger::TagActor(const AActor &Actor, bool bTagForSemanticSegmentation, uint32_t ActorID)
{
#ifdef CARLA_TAGGER_EXTRA_LOG
UE_LOG(LogCarla, Log, TEXT("Actor: %s"), *Actor.GetName());
UE_LOG(LogCarla, Log, TEXT("Actor: %s %d %d"), *Actor.GetName(), Actor.GetUniqueID(), ActorID);
#endif // CARLA_TAGGER_EXTRA_LOG

// Iterate static meshes.
Expand Down Expand Up @@ -152,7 +153,7 @@ void ATagger::TagActor(const AActor &Actor, bool bTagForSemanticSegmentation)
}

// Set tagged component color
FLinearColor Color = GetActorLabelColor(Actor, Label);
FLinearColor Color = GetLabelColor(ActorID, Label);
#ifdef CARLA_TAGGER_EXTRA_LOG
UE_LOG(LogCarla, Log, TEXT(" - Color: %s"), *Color.ToString());
#endif // CARLA_TAGGER_EXTRA_LOG
Expand Down Expand Up @@ -207,7 +208,7 @@ void ATagger::TagActor(const AActor &Actor, bool bTagForSemanticSegmentation)
}

// Set tagged component color
FLinearColor Color = GetActorLabelColor(Actor, Label);
FLinearColor Color = GetLabelColor(ActorID, Label);
#ifdef CARLA_TAGGER_EXTRA_LOG
UE_LOG(LogCarla, Log, TEXT(" - Color: %s"), *Color.ToString());
#endif // CARLA_TAGGER_EXTRA_LOG
Expand All @@ -219,17 +220,34 @@ void ATagger::TagActor(const AActor &Actor, bool bTagForSemanticSegmentation)
}
}

void ATagger::TagActorsInLevel(UWorld &World, const UCarlaEpisode &Episode, bool bTagForSemanticSegmentation)
{
for (TActorIterator<AActor> it(&World); it; ++it) {
uint32_t cActorId = (*it)->GetUniqueID();
FCarlaActor* cActor = Episode.FindCarlaActor(*it);
if (cActor) {
cActorId = cActor->GetActorId();
}
TagActor(**it, bTagForSemanticSegmentation, cActorId);
}
}

void ATagger::TagActorsInLevel(UWorld &World, bool bTagForSemanticSegmentation)
{
for (TActorIterator<AActor> it(&World); it; ++it) {
TagActor(**it, bTagForSemanticSegmentation);
TagActor(**it, bTagForSemanticSegmentation, (*it)->GetUniqueID());
}
}

void ATagger::TagActorsInLevel(ULevel &Level, bool bTagForSemanticSegmentation)
void ATagger::TagActorsInLevel(ULevel &Level, const UCarlaEpisode &Episode, bool bTagForSemanticSegmentation)
{
for (AActor * Actor : Level.Actors) {
TagActor(*Actor, bTagForSemanticSegmentation);
uint32_t cActorId = Actor->GetUniqueID();
FCarlaActor* cActor = Episode.FindCarlaActor(Actor);
if (cActor) {
cActorId = cActor->GetActorId();
}
TagActor(*Actor, bTagForSemanticSegmentation, cActorId);
}
}

Expand Down
9 changes: 6 additions & 3 deletions Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/Tagger.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@

namespace crp = carla::rpc;

class UCarlaEpisode;

/// Sets actors' custom depth stencil value for semantic segmentation according
/// to their meshes.
///
Expand All @@ -35,7 +37,7 @@ class CARLA_API ATagger : public AActor
/// pass is necessary for rendering the semantic segmentation. However, it may
/// add a performance penalty since occlusion doesn't seem to be applied to
/// objects having this value active.
static void TagActor(const AActor &Actor, bool bTagForSemanticSegmentation);
static void TagActor(const AActor &Actor, bool bTagForSemanticSegmentation, uint32_t ActorId);


/// Set the tag of every actor in level.
Expand All @@ -44,9 +46,10 @@ class CARLA_API ATagger : public AActor
/// pass is necessary for rendering the semantic segmentation. However, it may
/// add a performance penalty since occlusion doesn't seem to be applied to
/// objects having this value active.
static void TagActorsInLevel(UWorld &World, const UCarlaEpisode &Episode, bool bTagForSemanticSegmentation);
static void TagActorsInLevel(UWorld &World, bool bTagForSemanticSegmentation);

static void TagActorsInLevel(ULevel &Level, bool bTagForSemanticSegmentation);
static void TagActorsInLevel(ULevel &Level, const UCarlaEpisode &Episode, bool bTagForSemanticSegmentation);

/// Retrieve the tag of an already tagged component.
static crp::CityObjectLabel GetTagOfTaggedComponent(const UPrimitiveComponent &Component)
Expand Down Expand Up @@ -84,7 +87,7 @@ class CARLA_API ATagger : public AActor
static void SetStencilValue(UPrimitiveComponent &Component,
const crp::CityObjectLabel &Label, const bool bSetRenderCustomDepth);

static FLinearColor GetActorLabelColor(const AActor &Actor, const crp::CityObjectLabel &Label);
static FLinearColor GetLabelColor(const uint32_t ActorID, const crp::CityObjectLabel &Label);

static bool IsThing(const crp::CityObjectLabel &Label);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,6 @@ void UTaggerDelegate::RegisterSpawnHandler(UWorld *InWorld)
void UTaggerDelegate::OnActorSpawned(AActor* InActor)
{
if (InActor != nullptr) {
ATagger::TagActor(*InActor, bSemanticSegmentationEnabled);
ATagger::TagActor(*InActor, bSemanticSegmentationEnabled, InActor->GetUniqueID());
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -137,7 +137,8 @@ void ALargeMapManager::PostWorldOriginOffset(UWorld* InWorld, FIntVector InSrcOr
void ALargeMapManager::OnLevelAddedToWorld(ULevel* InLevel, UWorld* InWorld)
{
LM_LOG(Warning, "OnLevelAddedToWorld");
ATagger::TagActorsInLevel(*InLevel, true);
UCarlaEpisode* CarlaEpisode = UCarlaStatics::GetCurrentEpisode(InWorld);
ATagger::TagActorsInLevel(*InLevel, *CarlaEpisode, true);


//FDebug::DumpStackTraceToLog(ELogVerbosity::Log);
Expand Down
18 changes: 18 additions & 0 deletions Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@
#include <carla/rpc/ActorDefinition.h>
#include <carla/rpc/ActorDescription.h>
#include <carla/rpc/BoneTransformDataIn.h>
#include <carla/rpc/BoundingBox.h>
#include <carla/rpc/Command.h>
#include <carla/rpc/CommandResponse.h>
#include <carla/rpc/DebugShape.h>
Expand Down Expand Up @@ -1343,6 +1344,23 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_
return R<void>::Success();
};

BIND_SYNC(get_actor_bounding_box) << [this](
cr::ActorId ActorId) -> R<cr::BoundingBox>
{
REQUIRE_CARLA_EPISODE();
FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
if (!CarlaActor)
{
return RespondError(
"get_actor_bounding_box",
ECarlaServerResponse::ActorNotFound,
" Actor Id: " + FString::FromInt(ActorId));
}
FBoundingBox bounding_box = UBoundingBoxCalculator::GetActorBoundingBox(CarlaActor->GetActor(), 0);
bounding_box.ActorId = CarlaActor->GetActorId();
return cr::BoundingBox(bounding_box);
};

BIND_SYNC(get_actor_component_world_transform) << [this](
cr::ActorId ActorId,
const std::string componentName) -> R<cr::Transform>
Expand Down
2 changes: 2 additions & 0 deletions Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/BoundingBox.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,4 +24,6 @@ struct CARLA_API FBoundingBox
/// Rotation of the bounding box.
UPROPERTY(EditAnywhere, BlueprintReadWrite)
FRotator Rotation = {0.0f, 0.0f, 0.0f};

uint32_t ActorId = 0;
};
Loading

0 comments on commit e8947a4

Please sign in to comment.