LaneInvasionSensor stabilization

- Fix naming: Use 'LaneInvasionSensor'/'lane_invasion' instead of mixture with 'LaneDetector'/'lane_detector'
 - Create server-side LaneInvasionSensor (to be able to access it via ROS bridge)
This commit is contained in:
Pasch, Frederik 2019-03-27 09:36:45 +01:00
parent be481c4d03
commit b3bac35fbe
14 changed files with 88 additions and 38 deletions

View File

@ -1,5 +1,8 @@
## Latest Changes
* LaneInvasionSensor stabilization
- Fix naming: Use 'LaneInvasionSensor'/'lane_invasion' instead of mixture with 'LaneDetector'/'lane_detector'
- Create server-side LaneInvasionSensor (to be able to access it via ROS bridge)
* Fix ActorList returned by ActorList.Filter(...)
* Add --rolename to manual_control.py
* Migrate Content to AWS

View File

@ -48,7 +48,7 @@ This is the list of sensors currently available
* [sensor.camera.semantic_segmentation](#sensorcamerasemantic_segmentation)
* [sensor.lidar.ray_cast](#sensorlidarray_cast)
* [sensor.other.collision](#sensorothercollision)
* [sensor.other.lane_detector](#sensorotherlane_detector)
* [sensor.other.lane_invasion](#sensorotherlane_invasion)
* [sensor.other.obstacle](#sensorotherobstacle)
sensor.camera.rgb
@ -268,14 +268,14 @@ object for each collision registered
Note that several collision events might be registered during a single
simulation update.
sensor.other.lane_detector
sensor.other.lane_invasion
--------------------------
> _This sensor is a work in progress, currently very limited._
This sensor, when attached to an actor, it registers an event each time the
actor crosses a lane marking. This sensor is somehow special as it works fully
on the client-side. The lane detector uses the road data of the active map to
on the client-side. The lane invasion uses the road data of the active map to
determine whether a vehicle is invading another lane. This information is based
on the OpenDrive file provided by the map, therefore it is subject to the
fidelity of the OpenDrive description. In some places there might be

View File

@ -60,7 +60,7 @@ namespace client {
_geo_reference.Transform(GetLocation()));
} catch (const std::exception &e) {
/// @todo We need to unsubscribe the sensor.
// log_error("LaneDetector:", e.what());
// log_error("GnssSensor:", e.what());
return nullptr;
}
}

View File

@ -4,7 +4,7 @@
// This work is licensed under the terms of the MIT license.
// For a copy, see <https://opensource.org/licenses/MIT>.
#include "carla/client/LaneDetector.h"
#include "carla/client/LaneInvasionSensor.h"
#include "carla/Logging.h"
#include "carla/client/Map.h"
@ -40,9 +40,9 @@ namespace client {
location + Rotate(yaw, geom::Location(-box.extent.x, -box.extent.y, 0.0f))};
}
LaneDetector::~LaneDetector() = default;
LaneInvasionSensor::~LaneInvasionSensor() = default;
void LaneDetector::Listen(CallbackFunctionType callback) {
void LaneInvasionSensor::Listen(CallbackFunctionType callback) {
if (_is_listening) {
log_error(GetDisplayId(), ": already listening");
return;
@ -57,15 +57,15 @@ namespace client {
_map = GetWorld().GetMap();
DEBUG_ASSERT(_map != nullptr);
auto self = boost::static_pointer_cast<LaneDetector>(shared_from_this());
auto self = boost::static_pointer_cast<LaneInvasionSensor>(shared_from_this());
log_debug(GetDisplayId(), ": subscribing to tick event");
GetEpisode().Lock()->RegisterOnTickEvent([
cb=std::move(callback),
weak_self=WeakPtr<LaneDetector>(self)](const auto &timestamp) {
weak_self=WeakPtr<LaneInvasionSensor>(self)](const auto &timestamp) {
auto self = weak_self.lock();
if (self != nullptr) {
auto data = self->TickLaneDetector(timestamp);
auto data = self->TickLaneInvasionSensor(timestamp);
if (data != nullptr) {
cb(std::move(data));
}
@ -74,11 +74,12 @@ namespace client {
_is_listening = true;
}
void LaneDetector::Stop() {
throw_exception(std::runtime_error("LaneDetector::Stop(): not implemented."));
void LaneInvasionSensor::Stop() {
/// @todo We need unsubscribe from the world on tick.
_is_listening = false;
}
SharedPtr<sensor::SensorData> LaneDetector::TickLaneDetector(
SharedPtr<sensor::SensorData> LaneInvasionSensor::TickLaneInvasionSensor(
const Timestamp &timestamp) {
try {
const auto new_bounds = GetVehicleBounds(*_vehicle);
@ -98,7 +99,7 @@ namespace client {
crossed_lanes);
} catch (const std::exception &e) {
/// @todo We need to unsubscribe the sensor.
// log_error("LaneDetector:", e.what());
// log_error("LaneInvasionSensor:", e.what());
return nullptr;
}
}

View File

@ -17,12 +17,12 @@ namespace client {
class Map;
class Vehicle;
class LaneDetector final : public ClientSideSensor {
class LaneInvasionSensor final : public ClientSideSensor {
public:
using ClientSideSensor::ClientSideSensor;
~LaneDetector();
~LaneInvasionSensor();
/// Register a @a callback to be executed each time a new measurement is
/// received.
@ -43,7 +43,7 @@ namespace client {
private:
SharedPtr<sensor::SensorData> TickLaneDetector(const Timestamp &timestamp);
SharedPtr<sensor::SensorData> TickLaneInvasionSensor(const Timestamp &timestamp);
bool _is_listening = false;

View File

@ -10,7 +10,7 @@
#include "carla/StringUtil.h"
#include "carla/client/Actor.h"
#include "carla/client/GnssSensor.h"
#include "carla/client/LaneDetector.h"
#include "carla/client/LaneInvasionSensor.h"
#include "carla/client/ServerSideSensor.h"
#include "carla/client/TrafficLight.h"
#include "carla/client/TrafficSign.h"
@ -73,8 +73,8 @@ namespace detail {
SharedPtr<Actor> parent,
GarbageCollectionPolicy gc) {
auto init = ActorInitializer{description, episode, parent};
if (description.description.id == "sensor.other.lane_detector") { /// @todo
return MakeActorImpl<LaneDetector>(std::move(init), gc);
if (description.description.id == "sensor.other.lane_invasion") { /// @todo
return MakeActorImpl<LaneInvasionSensor>(std::move(init), gc);
} else if (description.description.id == "sensor.other.gnss") { /// @todo
return MakeActorImpl<GnssSensor>(std::move(init), gc);
} else if (description.HasAStream()) {

View File

@ -111,12 +111,6 @@ namespace detail {
SharedPtr<BlueprintLibrary> Simulator::GetBlueprintLibrary() {
auto defs = _client.GetActorDefinitions();
{ /// @todo
rpc::ActorDefinition def;
def.id = "sensor.other.lane_detector";
def.tags = "sensor,other,lane_detector";
defs.emplace_back(def);
}
return MakeShared<BlueprintLibrary>(std::move(defs));
}
@ -138,9 +132,7 @@ namespace detail {
Actor *parent,
GarbageCollectionPolicy gc) {
rpc::Actor actor;
if (blueprint.GetId() == "sensor.other.lane_detector") { /// @todo
actor.description = blueprint.MakeActorDescription();
} else if (parent != nullptr) {
if (parent != nullptr) {
actor = _client.SpawnActorWithParent(
blueprint.MakeActorDescription(),
transform,
@ -165,9 +157,7 @@ namespace detail {
bool Simulator::DestroyActor(Actor &actor) {
bool success = true;
if (actor.GetTypeId() != "sensor.other.lane_detector") { /// @todo
success = _client.DestroyActor(actor.GetId());
}
success = _client.DestroyActor(actor.GetId());
if (success) {
// Remove it's persistent state so it cannot access the client anymore.
actor.GetEpisode().Clear();

View File

@ -24,6 +24,7 @@
class ACollisionSensor;
class ADepthCamera;
class AGnssSensor;
class ALaneInvasionSensor;
class AObstacleDetectionSensor;
class ARayCastLidar;
class ASceneCaptureCamera;
@ -45,6 +46,7 @@ namespace sensor {
std::pair<ARayCastLidar *, s11n::LidarSerializer>,
std::pair<ACollisionSensor *, s11n::CollisionEventSerializer>,
std::pair<AGnssSensor *, s11n::ImageSerializer>,
std::pair<ALaneInvasionSensor *, s11n::ImageSerializer>,
std::pair<AObstacleDetectionSensor *, s11n::ObstacleDetectionEventSerializer>
>;
@ -63,6 +65,7 @@ namespace sensor {
#include "Carla/Sensor/SemanticSegmentationCamera.h"
#include "Carla/Sensor/WorldObserver.h"
#include "Carla/Sensor/GnssSensor.h"
#include "Carla/Sensor/LaneInvasionSensor.h"
#include "Carla/Sensor/ObstacleDetectionSensor.h"
#endif // LIBCARLA_SENSOR_REGISTRY_WITH_SENSOR_INCLUDES

View File

@ -572,7 +572,7 @@ class LaneInvasionSensor(object):
self._parent = parent_actor
self.hud = hud
world = self._parent.get_world()
bp = world.get_blueprint_library().find('sensor.other.lane_detector')
bp = world.get_blueprint_library().find('sensor.other.lane_invasion')
self.sensor = world.spawn_actor(bp, carla.Transform(), attach_to=self._parent)
# We need to pass the lambda a weak reference to self to avoid circular
# reference.

View File

@ -605,7 +605,7 @@ class LaneInvasionSensor(object):
self._parent = parent_actor
self.hud = hud
world = self._parent.get_world()
bp = world.get_blueprint_library().find('sensor.other.lane_detector')
bp = world.get_blueprint_library().find('sensor.other.lane_invasion')
self.sensor = world.spawn_actor(bp, carla.Transform(), attach_to=self._parent)
# We need to pass the lambda a weak reference to self to avoid circular
# reference.

View File

@ -617,7 +617,7 @@ class LaneInvasionSensor(object):
self._parent = parent_actor
self.hud = hud
world = self._parent.get_world()
bp = world.get_blueprint_library().find('sensor.other.lane_detector')
bp = world.get_blueprint_library().find('sensor.other.lane_invasion')
self.sensor = world.spawn_actor(bp, carla.Transform(), attach_to=self._parent)
# We need to pass the lambda a weak reference to self to avoid circular
# reference.

View File

@ -7,7 +7,7 @@
#include <carla/PythonUtil.h>
#include <carla/client/ClientSideSensor.h>
#include <carla/client/GnssSensor.h>
#include <carla/client/LaneDetector.h>
#include <carla/client/LaneInvasionSensor.h>
#include <carla/client/Sensor.h>
#include <carla/client/ServerSideSensor.h>
@ -36,8 +36,8 @@ void export_sensor() {
.def(self_ns::str(self_ns::self))
;
class_<cc::LaneDetector, bases<cc::ClientSideSensor>, boost::noncopyable, boost::shared_ptr<cc::LaneDetector>>
("LaneDetector", no_init)
class_<cc::LaneInvasionSensor, bases<cc::ClientSideSensor>, boost::noncopyable, boost::shared_ptr<cc::LaneInvasionSensor>>
("LaneInvasionSensor", no_init)
.def(self_ns::str(self_ns::self))
;

View File

@ -0,0 +1,26 @@
// Copyright (c) 2019 Intel Labs.
//
// 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/Sensor/LaneInvasionSensor.h"
#include "StaticMeshResources.h"
FActorDefinition ALaneInvasionSensor::GetSensorDefinition()
{
return UActorBlueprintFunctionLibrary::MakeGenericSensorDefinition(TEXT("other"), TEXT("lane_invasion"));
}
ALaneInvasionSensor::ALaneInvasionSensor(const FObjectInitializer &ObjectInitializer)
: Super(ObjectInitializer)
{
PrimaryActorTick.bCanEverTick = false;
auto MeshComp = CreateDefaultSubobject<UStaticMeshComponent>(TEXT("RootComponent"));
MeshComp->SetCollisionProfileName(UCollisionProfile::NoCollision_ProfileName);
MeshComp->bHiddenInGame = true;
MeshComp->CastShadow = false;
MeshComp->PostPhysicsComponentTick.bCanEverTick = false;
RootComponent = MeshComp;
}

View File

@ -0,0 +1,27 @@
// Copyright (c) 2019 Intel Labs.
//
// This work is licensed under the terms of the MIT license.
// For a copy, see <https://opensource.org/licenses/MIT>.
#pragma once
#include "Carla/Sensor/ShaderBasedSensor.h"
#include "Carla/Actor/ActorDefinition.h"
#include "LaneInvasionSensor.generated.h"
/// LaneInvasion sensor representation
/// The actual position calculation is done one client side
UCLASS()
class CARLA_API ALaneInvasionSensor : public ASensor
{
GENERATED_BODY()
public:
static FActorDefinition GetSensorDefinition();
ALaneInvasionSensor(const FObjectInitializer &ObjectInitializer);
};