Add bounding box to pedestrians
This commit is contained in:
parent
aec58e7357
commit
4235da52a2
|
@ -11,6 +11,10 @@
|
||||||
#include "carla/geom/Location.h"
|
#include "carla/geom/Location.h"
|
||||||
#include "carla/geom/Vector3D.h"
|
#include "carla/geom/Vector3D.h"
|
||||||
|
|
||||||
|
#ifdef LIBCARLA_INCLUDED_FROM_UE4
|
||||||
|
# include "Carla/Util/BoundingBox.h"
|
||||||
|
#endif // LIBCARLA_INCLUDED_FROM_UE4
|
||||||
|
|
||||||
namespace carla {
|
namespace carla {
|
||||||
namespace geom {
|
namespace geom {
|
||||||
|
|
||||||
|
@ -39,9 +43,9 @@ namespace geom {
|
||||||
|
|
||||||
#ifdef LIBCARLA_INCLUDED_FROM_UE4
|
#ifdef LIBCARLA_INCLUDED_FROM_UE4
|
||||||
|
|
||||||
BoundingBox(const FVector &Origin, const FVector &BoxExtent)
|
BoundingBox(const FBoundingBox &Box)
|
||||||
: location(Origin),
|
: location(Box.Origin),
|
||||||
extent(1e-2f * BoxExtent.X, 1e-2f * BoxExtent.Y, 1e-2f * BoxExtent.Z) {}
|
extent(1e-2f * Box.Extent.X, 1e-2f * Box.Extent.Y, 1e-2f * Box.Extent.Z) {}
|
||||||
|
|
||||||
#endif // LIBCARLA_INCLUDED_FROM_UE4
|
#endif // LIBCARLA_INCLUDED_FROM_UE4
|
||||||
|
|
||||||
|
|
|
@ -76,6 +76,7 @@ void export_actor() {
|
||||||
;
|
;
|
||||||
|
|
||||||
class_<cc::Walker, bases<cc::Actor>, boost::noncopyable, boost::shared_ptr<cc::Walker>>("Walker", no_init)
|
class_<cc::Walker, bases<cc::Actor>, boost::noncopyable, boost::shared_ptr<cc::Walker>>("Walker", no_init)
|
||||||
|
.add_property("bounding_box", CALL_RETURNING_COPY(cc::Walker, GetBoundingBox))
|
||||||
.def("apply_control", &cc::Walker::ApplyControl, (arg("control")))
|
.def("apply_control", &cc::Walker::ApplyControl, (arg("control")))
|
||||||
.def("get_control", &cc::Walker::GetWalkerControl)
|
.def("get_control", &cc::Walker::GetWalkerControl)
|
||||||
.def(self_ns::str(self_ns::self))
|
.def(self_ns::str(self_ns::self))
|
||||||
|
|
|
@ -8,6 +8,7 @@
|
||||||
#include "Carla/Server/TheNewCarlaServer.h"
|
#include "Carla/Server/TheNewCarlaServer.h"
|
||||||
|
|
||||||
#include "Carla/Sensor/Sensor.h"
|
#include "Carla/Sensor/Sensor.h"
|
||||||
|
#include "Carla/Util/BoundingBoxCalculator.h"
|
||||||
#include "Carla/Util/DebugShapeDrawer.h"
|
#include "Carla/Util/DebugShapeDrawer.h"
|
||||||
#include "Carla/Util/OpenDrive.h"
|
#include "Carla/Util/OpenDrive.h"
|
||||||
#include "Carla/Vehicle/CarlaWheeledVehicle.h"
|
#include "Carla/Vehicle/CarlaWheeledVehicle.h"
|
||||||
|
@ -114,30 +115,17 @@ private:
|
||||||
::AttachActors(Child.GetActor(), Parent.GetActor());
|
::AttachActors(Child.GetActor(), Parent.GetActor());
|
||||||
}
|
}
|
||||||
|
|
||||||
carla::geom::BoundingBox GetActorBoundingBox(const AActor &Actor)
|
|
||||||
{
|
|
||||||
/// @todo Bounding boxes only available for vehicles.
|
|
||||||
auto Vehicle = Cast<ACarlaWheeledVehicle>(&Actor);
|
|
||||||
if (Vehicle != nullptr)
|
|
||||||
{
|
|
||||||
FVector Location = Vehicle->GetVehicleBoundingBoxTransform().GetTranslation();
|
|
||||||
FVector Extent = Vehicle->GetVehicleBoundingBoxExtent();
|
|
||||||
return {Location, Extent};
|
|
||||||
}
|
|
||||||
return {};
|
|
||||||
}
|
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
|
||||||
carla::rpc::Actor SerializeActor(FActorView ActorView)
|
carla::rpc::Actor SerializeActor(FActorView ActorView)
|
||||||
{
|
{
|
||||||
carla::rpc::Actor Actor;
|
carla::rpc::Actor Actor;
|
||||||
Actor.id = ActorView.GetActorId();
|
Actor.id = ActorView.GetActorId();
|
||||||
if (ActorView.IsValid())
|
if (ActorView.IsValid() && !ActorView.GetActor()->IsPendingKill())
|
||||||
{
|
{
|
||||||
Actor.parent_id = Episode->GetActorRegistry().Find(ActorView.GetActor()->GetOwner()).GetActorId();
|
Actor.parent_id = Episode->GetActorRegistry().Find(ActorView.GetActor()->GetOwner()).GetActorId();
|
||||||
Actor.description = *ActorView.GetActorDescription();
|
Actor.description = *ActorView.GetActorDescription();
|
||||||
Actor.bounding_box = GetActorBoundingBox(*ActorView.GetActor());
|
Actor.bounding_box = UBoundingBoxCalculator::GetActorBoundingBox(ActorView.GetActor());
|
||||||
Actor.semantic_tags.reserve(ActorView.GetSemanticTags().Num());
|
Actor.semantic_tags.reserve(ActorView.GetSemanticTags().Num());
|
||||||
using tag_t = decltype(Actor.semantic_tags)::value_type;
|
using tag_t = decltype(Actor.semantic_tags)::value_type;
|
||||||
for (auto &&Tag : ActorView.GetSemanticTags())
|
for (auto &&Tag : ActorView.GetSemanticTags())
|
||||||
|
|
|
@ -0,0 +1,23 @@
|
||||||
|
// Copyright (c) 2017 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 "BoundingBox.generated.h"
|
||||||
|
|
||||||
|
USTRUCT(BlueprintType)
|
||||||
|
struct CARLA_API FBoundingBox
|
||||||
|
{
|
||||||
|
GENERATED_BODY()
|
||||||
|
|
||||||
|
/// Origin of the bounding box relative to its owner.
|
||||||
|
UPROPERTY(EditAnywhere, BlueprintReadWrite)
|
||||||
|
FVector Origin = {0.0f, 0.0f, 0.0f};
|
||||||
|
|
||||||
|
/// Radii extent of the bounding box.
|
||||||
|
UPROPERTY(EditAnywhere, BlueprintReadWrite)
|
||||||
|
FVector Extent = {0.0f, 0.0f, 0.0f};
|
||||||
|
};
|
|
@ -0,0 +1,44 @@
|
||||||
|
// Copyright (c) 2017 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>.
|
||||||
|
|
||||||
|
#include "Carla.h"
|
||||||
|
#include "Carla/Util/BoundingBoxCalculator.h"
|
||||||
|
|
||||||
|
#include "Carla/Vehicle/CarlaWheeledVehicle.h"
|
||||||
|
|
||||||
|
#include "Components/CapsuleComponent.h"
|
||||||
|
#include "GameFramework/Character.h"
|
||||||
|
|
||||||
|
FBoundingBox UBoundingBoxCalculator::GetActorBoundingBox(const AActor *Actor)
|
||||||
|
{
|
||||||
|
if (Actor != nullptr)
|
||||||
|
{
|
||||||
|
// Vehicle.
|
||||||
|
auto Vehicle = Cast<ACarlaWheeledVehicle>(Actor);
|
||||||
|
if (Vehicle != nullptr)
|
||||||
|
{
|
||||||
|
FVector Origin = Vehicle->GetVehicleBoundingBoxTransform().GetTranslation();
|
||||||
|
FVector Extent = Vehicle->GetVehicleBoundingBoxExtent();
|
||||||
|
return {Origin, Extent};
|
||||||
|
}
|
||||||
|
// Walker.
|
||||||
|
auto Character = Cast<ACharacter>(Actor);
|
||||||
|
if (Character != nullptr)
|
||||||
|
{
|
||||||
|
auto Capsule = Character->GetCapsuleComponent();
|
||||||
|
if (Capsule != nullptr)
|
||||||
|
{
|
||||||
|
const auto Radius = Capsule->GetScaledCapsuleRadius();
|
||||||
|
const auto HalfHeight = Capsule->GetScaledCapsuleHalfHeight();
|
||||||
|
// Characters have the pivot point centered.
|
||||||
|
FVector Origin = {0.0f, 0.0f, 0.0f};
|
||||||
|
FVector Extent = {Radius, Radius, HalfHeight};
|
||||||
|
return {Origin, Extent};
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return {};
|
||||||
|
}
|
|
@ -0,0 +1,30 @@
|
||||||
|
// Copyright (c) 2017 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/Util/BoundingBox.h"
|
||||||
|
|
||||||
|
#include "Kismet/BlueprintFunctionLibrary.h"
|
||||||
|
|
||||||
|
#include "BoundingBoxCalculator.generated.h"
|
||||||
|
|
||||||
|
class AActor;
|
||||||
|
|
||||||
|
UCLASS()
|
||||||
|
class CARLA_API UBoundingBoxCalculator : public UBlueprintFunctionLibrary
|
||||||
|
{
|
||||||
|
GENERATED_BODY()
|
||||||
|
|
||||||
|
public:
|
||||||
|
|
||||||
|
/// Compute the bounding box of the given Carla actor.
|
||||||
|
///
|
||||||
|
/// @warning If the actor type is not supported a default initialized bounding
|
||||||
|
/// box is returned.
|
||||||
|
UFUNCTION(Category = "Carla Actor", BlueprintCallable)
|
||||||
|
static FBoundingBox GetActorBoundingBox(const AActor *Actor);
|
||||||
|
};
|
Loading…
Reference in New Issue