Skip to content

Commit e8947a4

Browse files
AreopagXMinokoriDaraansergiopaniegoYlmdrin
authored
Instance segmentation (#8334)
* 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 <[email protected]> * 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 <[email protected]> Co-authored-by: Daniel <[email protected]> Co-authored-by: Sergio Paniego Blanco <[email protected]> Co-authored-by: Ylmdrin <[email protected]>
1 parent b60034b commit e8947a4

File tree

20 files changed

+125
-30
lines changed

20 files changed

+125
-30
lines changed

CHANGELOG.md

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,9 @@
2121
* Added named tuples for BasicAgent.py's detection result to allow for type-hints and better semantics.
2222
* Added type-hint support for the PythonAPI
2323
* Added type-hints to GlobalRoutePlanner and use carla.Vector3D code instead of pre 0.9.13 numpy code.
24-
24+
* If available, use ActorIDs instead of Unreal Engine IDs for instance segmentation
25+
* Synchronized actor BoundingBox between server and client
26+
* Add actor_id to bounding boxes
2527

2628
## CARLA 0.9.15
2729

Docs/adv_cpp_client.md

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -138,4 +138,3 @@ TOOLCHAIN=$(CURDIR)/ToolChain.cmake
138138

139139

140140

141-

LibCarla/source/carla/client/Actor.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,10 @@ namespace client {
3232
return GetEpisode().Lock()->GetActorAcceleration(*this);
3333
}
3434

35+
geom::BoundingBox Actor::GetBoundingBox() const {
36+
return GetEpisode().Lock()->GetActorBoundingBox(*this);
37+
}
38+
3539
geom::Transform Actor::GetComponentWorldTransform(const std::string componentName) const {
3640
return GetEpisode().Lock()->GetActorComponentWorldTransform(*this, componentName);
3741
}

LibCarla/source/carla/client/Actor.h

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,6 @@ namespace client {
2626
: LIBCARLA_INITIALIZE_LIFETIME_PROFILER(init.GetDisplayId()),
2727
Super(std::move(init)) {}
2828

29-
using ActorState::GetBoundingBox;
3029

3130
virtual ~Actor() = default;
3231

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

62+
geom::BoundingBox GetBoundingBox() const;
63+
6364
geom::Transform GetComponentWorldTransform(const std::string componentName) const;
6465

6566
geom::Transform GetComponentRelativeTransform(const std::string componentName) const;

LibCarla/source/carla/client/detail/Client.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -418,6 +418,10 @@ namespace detail {
418418
_pimpl->AsyncCall("add_actor_torque", actor, vector);
419419
}
420420

421+
geom::BoundingBox Client::GetActorBoundingBox(rpc::ActorId actor) {
422+
return _pimpl->CallAndWait<geom::BoundingBox>("get_actor_bounding_box", actor);
423+
}
424+
421425
geom::Transform Client::GetActorComponentWorldTransform(rpc::ActorId actor, const std::string componentName) {
422426
return _pimpl->CallAndWait<geom::Transform>("get_actor_component_world_transform", actor, componentName);
423427
}

LibCarla/source/carla/client/detail/Client.h

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -238,6 +238,9 @@ namespace detail {
238238
rpc::ActorId actor,
239239
const geom::Vector3D &vector);
240240

241+
geom::BoundingBox GetActorBoundingBox(
242+
rpc::ActorId actor);
243+
241244
geom::Transform GetActorComponentWorldTransform(
242245
rpc::ActorId actor,
243246
const std::string componentName);

LibCarla/source/carla/client/detail/Simulator.h

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -447,6 +447,10 @@ namespace detail {
447447
return GetActorSnapshot(actor).acceleration;
448448
}
449449

450+
geom::BoundingBox GetActorBoundingBox(const Actor &actor) {
451+
return _client.GetActorBoundingBox(actor.GetId());
452+
}
453+
450454
geom::Transform GetActorComponentWorldTransform(const Actor &actor, const std::string componentName) {
451455
return _client.GetActorComponentWorldTransform(actor.GetId(), componentName);
452456
}

LibCarla/source/carla/geom/BoundingBox.h

Lines changed: 10 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,12 @@ namespace geom {
3232
// -- Constructors ---------------------------------------------------------
3333
// =========================================================================
3434

35+
explicit BoundingBox(const Location &in_location, const Vector3D &in_extent, const Rotation &in_rotation, const uint32_t &in_actor_id)
36+
: location(in_location),
37+
extent(in_extent),
38+
rotation(in_rotation),
39+
actor_id(in_actor_id) {}
40+
3541
explicit BoundingBox(const Location &in_location, const Vector3D &in_extent, const Rotation &in_rotation)
3642
: location(in_location),
3743
extent(in_extent),
@@ -50,6 +56,7 @@ namespace geom {
5056
Location location; ///< Center of the BoundingBox in local space
5157
Vector3D extent; ///< Half the size of the BoundingBox in local space
5258
Rotation rotation; ///< Rotation of the BoundingBox in local space
59+
uint32_t actor_id;
5360

5461
// =========================================================================
5562
// -- Other methods --------------------------------------------------------
@@ -137,11 +144,12 @@ namespace geom {
137144
BoundingBox(const FBoundingBox &Box)
138145
: location(Box.Origin),
139146
extent(1e-2f * Box.Extent.X, 1e-2f * Box.Extent.Y, 1e-2f * Box.Extent.Z),
140-
rotation(Box.Rotation) {}
147+
rotation(Box.Rotation),
148+
actor_id(Box.ActorId) {}
141149

142150
#endif // LIBCARLA_INCLUDED_FROM_UE4
143151

144-
MSGPACK_DEFINE_ARRAY(location, extent, rotation);
152+
MSGPACK_DEFINE_ARRAY(location, extent, rotation, actor_id);
145153
};
146154

147155
} // namespace geom
Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,17 @@
1+
// Copyright (c) 2019 Computer Vision Center (CVC) at the Universitat Autonoma
2+
// de Barcelona (UAB).
3+
//
4+
// This work is licensed under the terms of the MIT license.
5+
// For a copy, see <https://opensource.org/licenses/MIT>.
6+
7+
#pragma once
8+
9+
#include "carla/geom/BoundingBox.h"
10+
11+
namespace carla {
12+
namespace rpc {
13+
14+
using BoundingBox = geom::BoundingBox;
15+
16+
} // namespace rpc
17+
} // namespace carla

PythonAPI/carla/source/libcarla/Geom.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -266,6 +266,7 @@ void export_geom() {
266266
.def_readwrite("location", &cg::BoundingBox::location)
267267
.def_readwrite("extent", &cg::BoundingBox::extent)
268268
.def_readwrite("rotation", &cg::BoundingBox::rotation)
269+
.def_readonly("actor_id", &cg::BoundingBox::actor_id)
269270
.def("contains", &cg::BoundingBox::Contains, arg("point"), arg("bbox_transform"))
270271
.def("get_local_vertices", CALL_RETURNING_LIST(cg::BoundingBox, GetLocalVertices))
271272
.def("get_world_vertices", CALL_RETURNING_LIST_1(cg::BoundingBox, GetWorldVertices, const cg::Transform&), arg("bbox_transform"))

0 commit comments

Comments
 (0)