Merge branch 'master' into NoRenderingMode

This commit is contained in:
Manish 2019-01-30 19:14:40 +01:00
commit 2f49b7ab6e
32 changed files with 1452 additions and 265 deletions

View File

@ -1,5 +1,7 @@
## Latest changes ## Latest changes
* Updated the Python API to enable the retrieval of a vehicle's speed limit and impacting traffic light
* Added functionality to the Python API to the allow control over traffic lights
* Upgraded to Unreal Engine 4.21 * Upgraded to Unreal Engine 4.21
* Upgraded Boost to 1.69.0 * Upgraded Boost to 1.69.0
* Added point transformation functionality for LibCarla and PythonAPI * Added point transformation functionality for LibCarla and PythonAPI
@ -10,12 +12,14 @@
* Added support for spawning and controlling walkers (pedestrians) * Added support for spawning and controlling walkers (pedestrians)
* Renamed vehicle.get_vehicle_control() to vehicle.get_control() to be consistent with walkers * Renamed vehicle.get_vehicle_control() to vehicle.get_control() to be consistent with walkers
* Remove crash reporter from packaged build * Remove crash reporter from packaged build
* Added sensor for detecting obstacles
* Added a few methods to manage an actor: * Added a few methods to manage an actor:
- set_velocity: for setting the linear velocity - set_velocity: for setting the linear velocity
- set_angular_velocity: for setting the angular velocity - set_angular_velocity: for setting the angular velocity
- get_angular_velocity: for getting the angular velocity - get_angular_velocity: for getting the angular velocity
- add_impulse: for applying an impulse (in world axis) - add_impulse: for applying an impulse (in world axis)
* Added support for gnss_sensor * Added support for gnss_sensor
* Fixed autopilot direction not properly initialized that interfered with the initial raycast direction
* Fixed TCP accept error, too many open files while creating and destroying a lot of sensors * Fixed TCP accept error, too many open files while creating and destroying a lot of sensors
* Fixed lost error messages in client-side, now when a request fails it reports the reason * Fixed lost error messages in client-side, now when a request fails it reports the reason
* Improved simulator fatal error handling, now uses UE4 fatal error system * Improved simulator fatal error handling, now uses UE4 fatal error system

View File

@ -46,6 +46,7 @@ This is the list of sensors currently available
* [sensor.lidar.ray_cast](#sensorlidarray_cast) * [sensor.lidar.ray_cast](#sensorlidarray_cast)
* [sensor.other.collision](#sensorothercollision) * [sensor.other.collision](#sensorothercollision)
* [sensor.other.lane_detector](#sensorotherlane_detector) * [sensor.other.lane_detector](#sensorotherlane_detector)
* [sensor.other.obstacle](#sensorotherobstacle)
sensor.camera.rgb sensor.camera.rgb
----------------- -----------------
@ -305,3 +306,26 @@ objects.
| `longitude` | double | Longitude position of the actor | | `longitude` | double | Longitude position of the actor |
| `altitude` | double | Altitude of the actor | | `altitude` | double | Altitude of the actor |
sensor.other.obstacle
---------------------
This sensor, when attached to an actor, reports if there is obstacles ahead.
| Blueprint attribute | Type | Default | Description |
| -------------------- | ---- | ------- | ----------- |
| `distance` | float | 5 | Distance to throw the trace to |
| `hit_radius` | float | 0.5 | Radius of the trace |
| `only_dynamics` | bool | false | If true, the trace will only look for dynamic objects |
| `debug_linetrace` | bool | false | If true, the trace will be visible |
| `sensor_tick` | float | 0.0 | Seconds between sensor captures (ticks) |
This sensor produces
[`carla.ObstacleDetectionSensorEvent`](python_api.md#carlaobstacledetectionsensoreventdata)
objects.
| Sensor data attribute | Type | Description |
| ---------------------- | ----------- | ----------- |
| `actor` | carla.Actor | Actor that detected the obstacle ("self" actor) |
| `other_actor` | carla.Actor | Actor detected as obstacle |
| `distance ` | float | Distance from actor to other_actor |

View File

@ -108,10 +108,25 @@
- `apply_control(vehicle_control)` - `apply_control(vehicle_control)`
- `get_control()` - `get_control()`
- `set_autopilot(enabled=True)` - `set_autopilot(enabled=True)`
- `get_speed_limit()`
- `get_traffic_light_state()`
- `is_at_traffic_light()`
- `get_traffic_light()`
## `carla.TrafficLight(carla.Actor)` ## `carla.TrafficLight(carla.Actor)`
- `state` - `state`
- `set_state(traffic_light_state)`
- `get_state()`
- `set_green_time(green_time)`
- `get_green_time()`
- `set_yellow_time(yellow_time)`
- `get_yellow_time()`
- `set_red_time(red_time)`
- `get_red_time()`
- `get_elapsed_time()`
- `freeze(True)`
- `is_frozen()`
## `carla.Sensor(carla.Actor)` ## `carla.Sensor(carla.Actor)`
@ -166,6 +181,12 @@
- `longitude` - `longitude`
- `altitude` - `altitude`
## `carla.ObstacleDetectionSensorEvent(carla.SensorData)`
- `actor`
- `other_actor`
- `distance`
## `carla.VehicleControl` ## `carla.VehicleControl`
- `throttle` - `throttle`
@ -303,10 +324,10 @@ Static presets
## `carla.TrafficLightState` ## `carla.TrafficLightState`
- `Off`
- `Red` - `Red`
- `Yellow` - `Yellow`
- `Green` - `Green`
- `Off`
- `Unknown` - `Unknown`
## `carla.LaneMarking` ## `carla.LaneMarking`

View File

@ -11,8 +11,48 @@
namespace carla { namespace carla {
namespace client { namespace client {
rpc::TrafficLightState TrafficLight::GetState() { void TrafficLight::SetState(rpc::TrafficLightState state) {
return GetEpisode().Lock()->GetActorDynamicState(*this).state.traffic_light_state; GetEpisode().Lock()->SetTrafficLightState(*this, state);
}
rpc::TrafficLightState TrafficLight::GetState() const {
return GetEpisode().Lock()->GetActorDynamicState(*this).state.traffic_light_data.state;
}
void TrafficLight::SetGreenTime(float green_time) {
GetEpisode().Lock()->SetTrafficLightGreenTime(*this, green_time);
}
float TrafficLight::GetGreenTime() const {
return GetEpisode().Lock()->GetActorDynamicState(*this).state.traffic_light_data.green_time;
}
void TrafficLight::SetYellowTime(float yellow_time) {
GetEpisode().Lock()->SetTrafficLightYellowTime(*this, yellow_time);
}
float TrafficLight::GetYellowTime() const {
return GetEpisode().Lock()->GetActorDynamicState(*this).state.traffic_light_data.yellow_time;
}
void TrafficLight::SetRedTime(float red_time) {
GetEpisode().Lock()->SetTrafficLightRedTime(*this, red_time);
}
float TrafficLight::GetRedTime() const {
return GetEpisode().Lock()->GetActorDynamicState(*this).state.traffic_light_data.red_time;
}
float TrafficLight::GetElapsedTime() const {
return GetEpisode().Lock()->GetActorDynamicState(*this).state.traffic_light_data.elapsed_time;
}
void TrafficLight::Freeze(bool freeze) {
GetEpisode().Lock()->FreezeTrafficLight(*this, freeze);
}
bool TrafficLight::IsFrozen() const {
return GetEpisode().Lock()->GetActorDynamicState(*this).state.traffic_light_data.time_is_frozen;
} }
} // namespace client } // namespace client

View File

@ -19,9 +19,30 @@ namespace client {
/// Return the current state of the traffic light. /// Return the current state of the traffic light.
/// ///
/// @note This function does not call the simulator, it returns the /// @note These functions do not call the simulator, they return the
/// traffic light state received in the last tick. /// data received in the last tick.
rpc::TrafficLightState GetState(); void SetState(rpc::TrafficLightState state);
rpc::TrafficLightState GetState() const;
void SetGreenTime(float green_time);
float GetGreenTime() const;
void SetYellowTime(float yellow_time);
float GetYellowTime() const;
void SetRedTime(float red_time);
float GetRedTime() const;
float GetElapsedTime() const;
void Freeze(bool freeze);
bool IsFrozen() const;
}; };
} // namespace client } // namespace client

View File

@ -7,6 +7,9 @@
#include "carla/client/Vehicle.h" #include "carla/client/Vehicle.h"
#include "carla/client/detail/Simulator.h" #include "carla/client/detail/Simulator.h"
#include "carla/client/ActorList.h"
#include "carla/client/TrafficLight.h"
#include "carla/rpc/TrafficLightState.h"
namespace carla { namespace carla {
namespace client { namespace client {
@ -23,7 +26,25 @@ namespace client {
} }
Vehicle::Control Vehicle::GetControl() const { Vehicle::Control Vehicle::GetControl() const {
return GetEpisode().Lock()->GetActorDynamicState(*this).state.vehicle_control; return GetEpisode().Lock()->GetActorDynamicState(*this).state.vehicle_data.control;
}
float Vehicle::GetSpeedLimit() const {
return GetEpisode().Lock()->GetActorDynamicState(*this).state.vehicle_data.speed_limit;
}
rpc::TrafficLightState Vehicle::GetTrafficLightState() const {
return GetEpisode().Lock()->GetActorDynamicState(*this).state.vehicle_data.traffic_light_state;
}
bool Vehicle::IsAtTrafficLight() {
return GetEpisode().Lock()->GetActorDynamicState(*this).state.vehicle_data.has_traffic_light;
}
SharedPtr<TrafficLight> Vehicle::GetTrafficLight() const {
auto id = GetEpisode().Lock()->GetActorDynamicState(*this).state.vehicle_data.traffic_light_id;
SharedPtr<Actor> actor = GetWorld().GetActors()->Find(id);
return boost::static_pointer_cast<TrafficLight>(actor);
} }
} // namespace client } // namespace client

View File

@ -8,9 +8,11 @@
#include "carla/client/Actor.h" #include "carla/client/Actor.h"
#include "carla/rpc/VehicleControl.h" #include "carla/rpc/VehicleControl.h"
#include "carla/rpc/TrafficLightState.h"
namespace carla { namespace carla {
namespace client { namespace client {
class TrafficLight;
class Vehicle : public Actor { class Vehicle : public Actor {
public: public:
@ -27,10 +29,20 @@ namespace client {
/// Return the control last applied to this vehicle. /// Return the control last applied to this vehicle.
/// ///
/// @note This function does not call the simulator, it returns the Control /// @note The following functions do not call the simulator, they return the
/// data
/// received in the last tick. /// received in the last tick.
//////////////////////////////////////////////////////////////////////////////////
Control GetControl() const; Control GetControl() const;
float GetSpeedLimit() const;
rpc::TrafficLightState GetTrafficLightState() const;
bool IsAtTrafficLight();
SharedPtr<TrafficLight> GetTrafficLight() const;
private: private:
Control _control; Control _control;

View File

@ -44,9 +44,9 @@ namespace detail {
worker_threads > 0u ? worker_threads : std::thread::hardware_concurrency()); worker_threads > 0u ? worker_threads : std::thread::hardware_concurrency());
} }
template <typename T, typename... Args> template <typename T, typename ... Args>
auto CallAndWait(const std::string &function, Args &&... args) { auto CallAndWait(const std::string &function, Args && ... args) {
auto object = rpc_client.call(function, std::forward<Args>(args)...); auto object = rpc_client.call(function, std::forward<Args>(args) ...);
using R = typename carla::rpc::Response<T>; using R = typename carla::rpc::Response<T>;
auto response = object.template as<R>(); auto response = object.template as<R>();
if (response.HasError()) { if (response.HasError()) {
@ -55,10 +55,10 @@ namespace detail {
return Get(response); return Get(response);
} }
template <typename... Args> template <typename ... Args>
void AsyncCall(const std::string &function, Args &&... args) { void AsyncCall(const std::string &function, Args && ... args) {
// Discard returned future. // Discard returned future.
rpc_client.async_call(function, std::forward<Args>(args)...); rpc_client.async_call(function, std::forward<Args>(args) ...);
} }
rpc::Client rpc_client; rpc::Client rpc_client;
@ -170,15 +170,37 @@ namespace detail {
_pimpl->AsyncCall("apply_control_to_walker", walker, control); _pimpl->AsyncCall("apply_control_to_walker", walker, control);
} }
void Client::SetActorVelocity(const rpc::Actor &actor, const geom::Vector3D &vector) { void Client::SetTrafficLightState(
const rpc::Actor &trafficLight,
const rpc::TrafficLightState trafficLightState) {
_pimpl->AsyncCall("set_traffic_light_state", trafficLight, trafficLightState);
}
void Client::SetTrafficLightGreenTime(const rpc::Actor &trafficLight, float greenTime) {
_pimpl->AsyncCall("set_traffic_light_green_time", trafficLight, greenTime);
}
void Client::SetTrafficLightYellowTime(const rpc::Actor &trafficLight, float yellowTime) {
_pimpl->AsyncCall("set_traffic_light_yellow_time", trafficLight, yellowTime);
}
void Client::SetTrafficLightRedTime(const rpc::Actor &trafficLight, float redTime) {
_pimpl->AsyncCall("set_traffic_light_red_time", trafficLight, redTime);
}
void Client::FreezeTrafficLight(const rpc::Actor &trafficLight, bool freeze) {
_pimpl->AsyncCall("freeze_traffic_light", trafficLight, freeze);
}
void Client::SetActorVelocity(const rpc::Actor &actor, const geom::Vector3D &vector) {
_pimpl->AsyncCall("set_actor_velocity", actor, vector); _pimpl->AsyncCall("set_actor_velocity", actor, vector);
} }
void Client::SetActorAngularVelocity(const rpc::Actor &actor, const geom::Vector3D &vector) { void Client::SetActorAngularVelocity(const rpc::Actor &actor, const geom::Vector3D &vector) {
_pimpl->AsyncCall("set_actor_angular_velocity", actor, vector); _pimpl->AsyncCall("set_actor_angular_velocity", actor, vector);
} }
void Client::AddActorImpulse(const rpc::Actor &actor, const geom::Vector3D &vector) { void Client::AddActorImpulse(const rpc::Actor &actor, const geom::Vector3D &vector) {
_pimpl->AsyncCall("add_actor_impulse", actor, vector); _pimpl->AsyncCall("add_actor_impulse", actor, vector);
} }

View File

@ -15,6 +15,7 @@
#include "carla/rpc/EpisodeInfo.h" #include "carla/rpc/EpisodeInfo.h"
#include "carla/rpc/MapInfo.h" #include "carla/rpc/MapInfo.h"
#include "carla/rpc/WeatherParameters.h" #include "carla/rpc/WeatherParameters.h"
#include "carla/rpc/TrafficLightState.h"
#include <functional> #include <functional>
#include <memory> #include <memory>
@ -30,8 +31,12 @@ namespace rpc {
class VehicleControl; class VehicleControl;
class WalkerControl; class WalkerControl;
} }
namespace sensor { class SensorData; } namespace sensor {
namespace streaming { class Token; } class SensorData;
}
namespace streaming {
class Token;
}
} }
namespace carla { namespace carla {
@ -107,6 +112,26 @@ namespace detail {
const rpc::Actor &walker, const rpc::Actor &walker,
const rpc::WalkerControl &control); const rpc::WalkerControl &control);
void SetTrafficLightState(
const rpc::Actor &trafficLight,
const rpc::TrafficLightState trafficLightState);
void SetTrafficLightGreenTime(
const rpc::Actor &trafficLight,
float greenTime);
void SetTrafficLightYellowTime(
const rpc::Actor &trafficLight,
float yellowTime);
void SetTrafficLightRedTime(
const rpc::Actor &trafficLight,
float redTime);
void FreezeTrafficLight(
const rpc::Actor &trafficLight,
bool freeze);
void SetActorVelocity( void SetActorVelocity(
const rpc::Actor &actor, const rpc::Actor &actor,
const geom::Vector3D &vector); const geom::Vector3D &vector);

View File

@ -18,6 +18,8 @@
#include "carla/client/detail/Episode.h" #include "carla/client/detail/Episode.h"
#include "carla/client/detail/EpisodeProxy.h" #include "carla/client/detail/EpisodeProxy.h"
#include "carla/profiler/LifetimeProfiled.h" #include "carla/profiler/LifetimeProfiled.h"
#include "carla/client/TrafficLight.h"
#include "carla/rpc/TrafficLightState.h"
#include <memory> #include <memory>
@ -235,6 +237,31 @@ namespace detail {
void UnSubscribeFromSensor(const Sensor &sensor); void UnSubscribeFromSensor(const Sensor &sensor);
/// @}
// =========================================================================
/// @name Operations with traffic lights
// =========================================================================
/// @{
void SetTrafficLightState(TrafficLight &trafficLight, const rpc::TrafficLightState trafficLightState) {
_client.SetTrafficLightState(trafficLight.Serialize(), trafficLightState);
}
void SetTrafficLightGreenTime(TrafficLight &trafficLight, float greenTime) {
_client.SetTrafficLightGreenTime(trafficLight.Serialize(), greenTime);
}
void SetTrafficLightYellowTime(TrafficLight &trafficLight, float yellowTime) {
_client.SetTrafficLightYellowTime(trafficLight.Serialize(), yellowTime);
}
void SetTrafficLightRedTime(TrafficLight &trafficLight, float redTime) {
_client.SetTrafficLightRedTime(trafficLight.Serialize(), redTime);
}
void FreezeTrafficLight(TrafficLight &trafficLight, bool freeze) {
_client.FreezeTrafficLight(trafficLight.Serialize(), freeze);
}
/// @} /// @}
// ========================================================================= // =========================================================================
/// @name Debug /// @name Debug

View File

@ -14,11 +14,10 @@ namespace carla {
namespace rpc { namespace rpc {
enum class TrafficLightState : uint8_t { enum class TrafficLightState : uint8_t {
Off,
Red, Red,
Yellow, Yellow,
Green, Green,
Off,
Unknown, Unknown,
SIZE SIZE
}; };

View File

@ -18,6 +18,7 @@
#include "carla/sensor/s11n/EpisodeStateSerializer.h" #include "carla/sensor/s11n/EpisodeStateSerializer.h"
#include "carla/sensor/s11n/ImageSerializer.h" #include "carla/sensor/s11n/ImageSerializer.h"
#include "carla/sensor/s11n/LidarSerializer.h" #include "carla/sensor/s11n/LidarSerializer.h"
#include "carla/sensor/s11n/ObstacleDetectionEventSerializer.h"
// 2. Add a forward-declaration of the sensor here. // 2. Add a forward-declaration of the sensor here.
class ACollisionSensor; class ACollisionSensor;
@ -27,6 +28,7 @@ class ASceneCaptureCamera;
class ASemanticSegmentationCamera; class ASemanticSegmentationCamera;
class AWorldObserver; class AWorldObserver;
class AGnssSensor; class AGnssSensor;
class AObstacleDetectionSensor;
namespace carla { namespace carla {
namespace sensor { namespace sensor {
@ -42,7 +44,8 @@ namespace sensor {
std::pair<ASemanticSegmentationCamera *, s11n::ImageSerializer>, std::pair<ASemanticSegmentationCamera *, s11n::ImageSerializer>,
std::pair<ARayCastLidar *, s11n::LidarSerializer>, std::pair<ARayCastLidar *, s11n::LidarSerializer>,
std::pair<ACollisionSensor *, s11n::CollisionEventSerializer>, std::pair<ACollisionSensor *, s11n::CollisionEventSerializer>,
std::pair<AGnssSensor *, s11n::ImageSerializer> std::pair<AGnssSensor *, s11n::ImageSerializer>,
std::pair<AObstacleDetectionSensor *, s11n::ObstacleDetectionEventSerializer>
>; >;
} // namespace sensor } // namespace sensor
@ -60,5 +63,6 @@ namespace sensor {
#include "Carla/Sensor/SemanticSegmentationCamera.h" #include "Carla/Sensor/SemanticSegmentationCamera.h"
#include "Carla/Sensor/WorldObserver.h" #include "Carla/Sensor/WorldObserver.h"
#include "Carla/Sensor/GnssSensor.h" #include "Carla/Sensor/GnssSensor.h"
#include "Carla/Sensor/ObstacleDetectionSensor.h"
#endif // LIBCARLA_SENSOR_REGISTRY_WITH_SENSOR_INCLUDES #endif // LIBCARLA_SENSOR_REGISTRY_WITH_SENSOR_INCLUDES

View File

@ -50,6 +50,19 @@ namespace detail {
bool manual_gear_shift; bool manual_gear_shift;
int32_t gear; int32_t gear;
}; };
#pragma pack(pop)
#pragma pack(push, 1)
struct VehicleData {
VehicleData() = default;
PackedVehicleControl control;
float speed_limit;
rpc::TrafficLightState traffic_light_state;
bool has_traffic_light;
rpc::actor_id_type traffic_light_id;
};
#pragma pack(pop) #pragma pack(pop)
#pragma pack(push, 1) #pragma pack(push, 1)
@ -73,8 +86,21 @@ namespace detail {
float speed; float speed;
bool jump; bool jump;
}; };
#pragma pack(pop) #pragma pack(pop)
#pragma pack(push, 1)
struct TrafficLightData {
TrafficLightData() = default;
rpc::TrafficLightState state;
float green_time;
float yellow_time;
float red_time;
float elapsed_time;
bool time_is_frozen;
};
#pragma pack(pop)
} // namespace detail } // namespace detail
#pragma pack(push, 1) #pragma pack(push, 1)
@ -91,8 +117,8 @@ namespace detail {
geom::Vector3D angular_velocity; geom::Vector3D angular_velocity;
union TypeDependentState { union TypeDependentState {
rpc::TrafficLightState traffic_light_state; detail::TrafficLightData traffic_light_data;
detail::PackedVehicleControl vehicle_control; detail::VehicleData vehicle_data;
detail::PackedWalkerControl walker_control; detail::PackedWalkerControl walker_control;
} state; } state;
}; };
@ -100,7 +126,7 @@ namespace detail {
#pragma pack(pop) #pragma pack(pop)
static_assert( static_assert(
sizeof(ActorDynamicState) == 13u * sizeof(uint32_t) + sizeof(detail::PackedVehicleControl), sizeof(ActorDynamicState) == 13u * sizeof(uint32_t) + sizeof(detail::VehicleData),
"Invalid ActorDynamicState size!"); "Invalid ActorDynamicState size!");
} // namespace data } // namespace data

View File

@ -0,0 +1,68 @@
// 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/Debug.h"
#include "carla/client/detail/ActorVariant.h"
#include "carla/sensor/SensorData.h"
#include "carla/sensor/s11n/ObstacleDetectionEventSerializer.h"
namespace carla {
namespace sensor {
namespace data {
/// A registered detection.
class ObstacleDetectionEvent : public SensorData {
using Super = SensorData;
protected:
using Serializer = s11n::ObstacleDetectionEventSerializer;
friend Serializer;
explicit ObstacleDetectionEvent(const RawData &data)
: Super(data),
//_deserialized_data(),
_self_actor(nullptr),
_other_actor(nullptr) {
auto ddata = Serializer::DeserializeRawData(data);
_self_actor = std::move(ddata.self_actor);
_other_actor = std::move(ddata.other_actor);
_distance = ddata.distance;
}
public:
/// Get "self" actor. Actor that measured the collision.
SharedPtr<client::Actor> GetActor() const {
return _self_actor.Get(GetEpisode());
}
/// Get the actor to which we collided.
SharedPtr<client::Actor> GetOtherActor() const {
return _other_actor.Get(GetEpisode());
}
/// Normal impulse result of the collision.
float GetDistance() const {
return _distance;
}
private:
client::detail::ActorVariant _self_actor;
client::detail::ActorVariant _other_actor;
float _distance;
};
} // namespace data
} // namespace sensor
} // namespace carla

View File

@ -0,0 +1,20 @@
// 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/sensor/data/ObstacleDetectionEvent.h"
#include "carla/sensor/s11n/ObstacleDetectionEventSerializer.h"
namespace carla {
namespace sensor {
namespace s11n {
SharedPtr<SensorData> ObstacleDetectionEventSerializer::Deserialize(RawData data) {
return SharedPtr<SensorData>(new data::ObstacleDetectionEvent(std::move(data)));
}
} // namespace s11n
} // namespace sensor
} // namespace carla

View File

@ -0,0 +1,57 @@
// 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/Buffer.h"
#include "carla/Debug.h"
#include "carla/Memory.h"
#include "carla/rpc/Actor.h"
#include "carla/sensor/RawData.h"
namespace carla {
namespace sensor {
class SensorData;
namespace s11n {
/// Serializes the current state of the whole episode.
class ObstacleDetectionEventSerializer {
public:
struct Data {
rpc::Actor self_actor;
rpc::Actor other_actor;
float distance;
MSGPACK_DEFINE_ARRAY(self_actor, other_actor, distance)
};
constexpr static auto header_offset = 0u;
static Data DeserializeRawData(const RawData &message) {
return MsgPack::UnPack<Data>(message.begin(), message.size());
}
template <typename SensorT>
static Buffer Serialize(
const SensorT &,
rpc::Actor self_actor,
rpc::Actor other_actor,
float distance) {
return MsgPack::Pack(Data{self_actor, other_actor, distance});
}
static SharedPtr<SensorData> Deserialize(RawData data);
};
} // namespace s11n
} // namespace sensor
} // namespace carla

View File

@ -37,65 +37,83 @@ void export_actor() {
namespace cr = carla::rpc; namespace cr = carla::rpc;
class_<std::vector<int>>("vector_of_ints") class_<std::vector<int>>("vector_of_ints")
.def(vector_indexing_suite<std::vector<int>>()) .def(vector_indexing_suite<std::vector<int>>())
.def(self_ns::str(self_ns::self)) .def(self_ns::str(self_ns::self))
; ;
class_<cc::Actor, boost::noncopyable, boost::shared_ptr<cc::Actor>>("Actor", no_init) class_<cc::Actor, boost::noncopyable, boost::shared_ptr<cc::Actor>>("Actor", no_init)
// work-around, force return copy to resolve Actor instead of ActorState. // work-around, force return copy to resolve Actor instead of ActorState.
.add_property("id", CALL_RETURNING_COPY(cc::Actor, GetId)) .add_property("id", CALL_RETURNING_COPY(cc::Actor, GetId))
.add_property("type_id", CALL_RETURNING_COPY(cc::Actor, GetTypeId)) .add_property("type_id", CALL_RETURNING_COPY(cc::Actor, GetTypeId))
.add_property("parent", CALL_RETURNING_COPY(cc::Actor, GetParent)) .add_property("parent", CALL_RETURNING_COPY(cc::Actor, GetParent))
.add_property("semantic_tags", &GetSemanticTags) .add_property("semantic_tags", &GetSemanticTags)
.add_property("is_alive", CALL_RETURNING_COPY(cc::Actor, IsAlive)) .add_property("is_alive", CALL_RETURNING_COPY(cc::Actor, IsAlive))
.add_property("attributes", +[](const cc::Actor &self) { .add_property("attributes", +[] (const cc::Actor &self) {
boost::python::dict atttribute_dict; boost::python::dict atttribute_dict;
for (auto &&attribute_value : self.GetAttributes()) { for (auto &&attribute_value : self.GetAttributes()) {
atttribute_dict[attribute_value.GetId()] = attribute_value.GetValue(); atttribute_dict[attribute_value.GetId()] = attribute_value.GetValue();
} }
return atttribute_dict; return atttribute_dict;
}) })
.def("get_world", CALL_RETURNING_COPY(cc::Actor, GetWorld)) .def("get_world", CALL_RETURNING_COPY(cc::Actor, GetWorld))
.def("get_location", &cc::Actor::GetLocation) .def("get_location", &cc::Actor::GetLocation)
.def("get_transform", &cc::Actor::GetTransform) .def("get_transform", &cc::Actor::GetTransform)
.def("get_velocity", &cc::Actor::GetVelocity) .def("get_velocity", &cc::Actor::GetVelocity)
.def("get_angular_velocity", &cc::Actor::GetAngularVelocity) .def("get_angular_velocity", &cc::Actor::GetAngularVelocity)
.def("get_acceleration", &cc::Actor::GetAcceleration) .def("get_acceleration", &cc::Actor::GetAcceleration)
.def("set_location", &cc::Actor::SetLocation, (arg("location"))) .def("set_location", &cc::Actor::SetLocation, (arg("location")))
.def("set_transform", &cc::Actor::SetTransform, (arg("transform"))) .def("set_transform", &cc::Actor::SetTransform, (arg("transform")))
.def("set_velocity", &cc::Actor::SetVelocity, (arg("vector"))) .def("set_velocity", &cc::Actor::SetVelocity, (arg("vector")))
.def("set_angular_velocity", &cc::Actor::SetAngularVelocity, (arg("vector"))) .def("set_angular_velocity", &cc::Actor::SetAngularVelocity, (arg("vector")))
.def("add_impulse", &cc::Actor::AddImpulse, (arg("vector"))) .def("add_impulse", &cc::Actor::AddImpulse, (arg("vector")))
.def("set_simulate_physics", &cc::Actor::SetSimulatePhysics, (arg("enabled")=true)) .def("set_simulate_physics", &cc::Actor::SetSimulatePhysics, (arg("enabled") = true))
.def("destroy", CALL_WITHOUT_GIL(cc::Actor, Destroy)) .def("destroy", CALL_WITHOUT_GIL(cc::Actor, Destroy))
.def(self_ns::str(self_ns::self)) .def(self_ns::str(self_ns::self))
; ;
class_<cc::Vehicle, bases<cc::Actor>, boost::noncopyable, boost::shared_ptr<cc::Vehicle>>("Vehicle", no_init) class_<cc::Vehicle, bases<cc::Actor>, boost::noncopyable, boost::shared_ptr<cc::Vehicle>>("Vehicle",
.add_property("bounding_box", CALL_RETURNING_COPY(cc::Vehicle, GetBoundingBox)) no_init)
.def("apply_control", &cc::Vehicle::ApplyControl, (arg("control"))) .add_property("bounding_box", CALL_RETURNING_COPY(cc::Vehicle, GetBoundingBox))
.def("get_control", &cc::Vehicle::GetControl) .def("apply_control", &cc::Vehicle::ApplyControl, (arg("control")))
.def("set_autopilot", &cc::Vehicle::SetAutopilot, (arg("enabled")=true)) .def("get_control", &cc::Vehicle::GetControl)
.def(self_ns::str(self_ns::self)) .def("set_autopilot", &cc::Vehicle::SetAutopilot, (arg("enabled") = true))
.def("get_speed_limit", &cc::Vehicle::GetSpeedLimit)
.def("get_traffic_light_state", &cc::Vehicle::GetTrafficLightState)
.def("is_at_traffic_light", &cc::Vehicle::IsAtTrafficLight)
.def("get_traffic_light", &cc::Vehicle::GetTrafficLight)
.def(self_ns::str(self_ns::self))
; ;
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)) .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))
; ;
enum_<cr::TrafficLightState>("TrafficLightState") enum_<cr::TrafficLightState>("TrafficLightState")
.value("Off", cr::TrafficLightState::Off) .value("Red", cr::TrafficLightState::Red)
.value("Red", cr::TrafficLightState::Red) .value("Yellow", cr::TrafficLightState::Yellow)
.value("Yellow", cr::TrafficLightState::Yellow) .value("Green", cr::TrafficLightState::Green)
.value("Green", cr::TrafficLightState::Green) .value("Off", cr::TrafficLightState::Off)
.value("Unknown", cr::TrafficLightState::Unknown) .value("Unknown", cr::TrafficLightState::Unknown)
; ;
class_<cc::TrafficLight, bases<cc::Actor>, boost::noncopyable, boost::shared_ptr<cc::TrafficLight>>("TrafficLight", no_init) class_<cc::TrafficLight, bases<cc::Actor>, boost::noncopyable, boost::shared_ptr<cc::TrafficLight>>(
.add_property("state", &cc::TrafficLight::GetState) "TrafficLight",
.def(self_ns::str(self_ns::self)) no_init)
.add_property("state", &cc::TrafficLight::GetState)
.def("set_state", &cc::TrafficLight::SetState, (arg("state")))
.def("get_state", &cc::TrafficLight::GetState)
.def("set_green_time", &cc::TrafficLight::SetGreenTime, (arg("green_time")))
.def("get_green_time", &cc::TrafficLight::GetGreenTime)
.def("set_yellow_time", &cc::TrafficLight::SetYellowTime, (arg("yellow_time")))
.def("get_yellow_time", &cc::TrafficLight::GetYellowTime)
.def("set_red_time", &cc::TrafficLight::SetRedTime, (arg("red_time")))
.def("get_red_time", &cc::TrafficLight::GetRedTime)
.def("get_elapsed_time", &cc::TrafficLight::GetElapsedTime)
.def("freeze", &cc::TrafficLight::Freeze, (arg("freeze")))
.def("is_frozen", &cc::TrafficLight::IsFrozen)
.def(self_ns::str(self_ns::self))
; ;
} }

View File

@ -11,6 +11,7 @@
#include <carla/pointcloud/PointCloudIO.h> #include <carla/pointcloud/PointCloudIO.h>
#include <carla/sensor/SensorData.h> #include <carla/sensor/SensorData.h>
#include <carla/sensor/data/CollisionEvent.h> #include <carla/sensor/data/CollisionEvent.h>
#include <carla/sensor/data/ObstacleDetectionEvent.h>
#include <carla/sensor/data/Image.h> #include <carla/sensor/data/Image.h>
#include <carla/sensor/data/LaneInvasionEvent.h> #include <carla/sensor/data/LaneInvasionEvent.h>
#include <carla/sensor/data/LidarMeasurement.h> #include <carla/sensor/data/LidarMeasurement.h>
@ -46,6 +47,13 @@ namespace data {
return out; return out;
} }
std::ostream &operator<<(std::ostream &out, const ObstacleDetectionEvent &meas) {
out << "ObstacleDetectionEvent(frame=" << meas.GetFrameNumber()
<< ", other_actor=" << meas.GetOtherActor()
<< ')';
return out;
}
std::ostream &operator<<(std::ostream &out, const LaneInvasionEvent &meas) { std::ostream &operator<<(std::ostream &out, const LaneInvasionEvent &meas) {
out << "LaneInvasionEvent(frame=" << meas.GetFrameNumber() << ')'; out << "LaneInvasionEvent(frame=" << meas.GetFrameNumber() << ')';
return out; return out;
@ -200,6 +208,13 @@ void export_sensor_data() {
.def(self_ns::str(self_ns::self)) .def(self_ns::str(self_ns::self))
; ;
class_<csd::ObstacleDetectionEvent, bases<cs::SensorData>, boost::noncopyable, boost::shared_ptr<csd::ObstacleDetectionEvent>>("ObstacleDetectionEvent", no_init)
.add_property("actor", &csd::ObstacleDetectionEvent::GetActor)
.add_property("other_actor", &csd::ObstacleDetectionEvent::GetOtherActor)
.add_property("distance", CALL_RETURNING_COPY(csd::ObstacleDetectionEvent, GetDistance))
.def(self_ns::str(self_ns::self))
;
enum_<cre::LaneMarking>("LaneMarking") enum_<cre::LaneMarking>("LaneMarking")
.value("Other", cre::LaneMarking::Other) .value("Other", cre::LaneMarking::Other)
.value("Broken", cre::LaneMarking::Broken) .value("Broken", cre::LaneMarking::Broken)

View File

@ -441,6 +441,82 @@ void UActorBlueprintFunctionLibrary::MakePedestrianDefinitions(
FillActorDefinitionArray(ParameterArray, Definitions, &MakePedestrianDefinition); FillActorDefinitionArray(ParameterArray, Definitions, &MakePedestrianDefinition);
} }
void UActorBlueprintFunctionLibrary::MakePropDefinition(
const FPropParameters &Parameters,
bool &Success,
FActorDefinition &Definition)
{
/// @todo We need to validate here the params.
FillIdAndTags(Definition, TEXT("static"), TEXT("prop"), Parameters.Name);
AddRecommendedValuesForActorRoleName(Definition, {TEXT("prop")});
auto GetSize = [](EPropSize Value) {
switch (Value)
{
case EPropSize::Tiny: return TEXT("tiny");
case EPropSize::Small: return TEXT("small");
case EPropSize::Medium: return TEXT("medium");
case EPropSize::Big: return TEXT("big");
case EPropSize::Huge: return TEXT("huge");
default: return TEXT("unknown");
}
};
Definition.Attributes.Emplace(FActorAttribute{
TEXT("size"),
EActorAttributeType::String,
GetSize(Parameters.Size)});
Success = CheckActorDefinition(Definition);
}
void UActorBlueprintFunctionLibrary::MakePropDefinitions(
const TArray<FPropParameters> &ParameterArray,
TArray<FActorDefinition> &Definitions)
{
FillActorDefinitionArray(ParameterArray, Definitions, &MakePropDefinition);
}
void UActorBlueprintFunctionLibrary::MakeObstacleDetectorDefinitions(
const FString &Type,
const FString &Id,
FActorDefinition &Definition)
{
Definition = MakeGenericSensorDefinition(TEXT("other"), TEXT("obstacle"));
AddVariationsForSensor(Definition);
// Distance.
FActorVariation distance;
distance.Id = TEXT("distance");
distance.Type = EActorAttributeType::Float;
distance.RecommendedValues = { TEXT("5.0") };
distance.bRestrictToRecommended = false;
// HitRadius.
FActorVariation hitradius;
hitradius.Id = TEXT("hit_radius");
hitradius.Type = EActorAttributeType::Float;
hitradius.RecommendedValues = { TEXT("0.5") };
hitradius.bRestrictToRecommended = false;
// Only Dynamics
FActorVariation onlydynamics;
onlydynamics.Id = TEXT("only_dynamics");
onlydynamics.Type = EActorAttributeType::Bool;
onlydynamics.RecommendedValues = { TEXT("false") };
onlydynamics.bRestrictToRecommended = false;
// Debug Line Trace
FActorVariation debuglinetrace;
debuglinetrace.Id = TEXT("debug_linetrace");
debuglinetrace.Type = EActorAttributeType::Bool;
debuglinetrace.RecommendedValues = { TEXT("false") };
debuglinetrace.bRestrictToRecommended = false;
Definition.Variations.Append({
distance,
hitradius,
onlydynamics,
debuglinetrace
});
}
/// ============================================================================ /// ============================================================================
/// -- Helpers to retrieve attribute values ------------------------------------ /// -- Helpers to retrieve attribute values ------------------------------------
/// ============================================================================ /// ============================================================================

View File

@ -9,6 +9,7 @@
#include "Carla/Actor/ActorDefinition.h" #include "Carla/Actor/ActorDefinition.h"
#include "Carla/Actor/ActorDescription.h" #include "Carla/Actor/ActorDescription.h"
#include "Carla/Actor/PedestrianParameters.h" #include "Carla/Actor/PedestrianParameters.h"
#include "Carla/Actor/PropParameters.h"
#include "Carla/Actor/VehicleParameters.h" #include "Carla/Actor/VehicleParameters.h"
#include "Kismet/BlueprintFunctionLibrary.h" #include "Kismet/BlueprintFunctionLibrary.h"
@ -91,6 +92,23 @@ public:
const TArray<FPedestrianParameters> &ParameterArray, const TArray<FPedestrianParameters> &ParameterArray,
TArray<FActorDefinition> &Definitions); TArray<FActorDefinition> &Definitions);
UFUNCTION(Category = "Carla Actor", BlueprintCallable)
static void MakePropDefinition(
const FPropParameters &Parameters,
bool &Success,
FActorDefinition &Definition);
UFUNCTION(Category = "Carla Actor", BlueprintCallable)
static void MakePropDefinitions(
const TArray<FPropParameters> &ParameterArray,
TArray<FActorDefinition> &Definitions);
UFUNCTION()
static void MakeObstacleDetectorDefinitions(
const FString &Type,
const FString &Id,
FActorDefinition &Definition);
/// @} /// @}
/// ========================================================================== /// ==========================================================================
/// @name Helpers to retrieve attribute values /// @name Helpers to retrieve attribute values

View File

@ -0,0 +1,40 @@
// 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 "Engine/StaticMesh.h"
#include "PropParameters.generated.h"
UENUM(BlueprintType)
enum class EPropSize : uint8
{
Tiny UMETA(DisplayName = "Tiny", ToolTip = "Smaller than a mailbox"),
Small UMETA(DisplayName = "Small", ToolTip = "Size of a mailbox"),
Medium UMETA(DisplayName = "Medium", ToolTip = "Size of a human"),
Big UMETA(DisplayName = "Big", ToolTip = "Size of a bus stop"),
Huge UMETA(DisplayName = "Huge", ToolTip = "Size of a house or bigger"),
SIZE UMETA(Hidden),
INVALID UMETA(DisplayName = "INVALID")
};
USTRUCT(BlueprintType)
struct CARLA_API FPropParameters
{
GENERATED_BODY()
UPROPERTY(EditAnywhere, BlueprintReadWrite)
FString Name;
UPROPERTY(EditAnywhere, BlueprintReadWrite)
UStaticMesh *Mesh;
UPROPERTY(EditAnywhere, BlueprintReadWrite)
EPropSize Size = EPropSize::INVALID;
};

View File

@ -169,50 +169,75 @@ void AOpenDriveActor::BuildRoutes()
const std::vector<Waypoint> MapLaneBeginWaypoint = const std::vector<Waypoint> MapLaneBeginWaypoint =
WaypointGen::GenerateLaneEnd(*map_ptr); WaypointGen::GenerateLaneEnd(*map_ptr);
// Since we are going to iterate all the successors of all the lanes, we need
// a vector to store the already visited lanes. Lanes can be successors of
// multiple other lanes
std::vector<std::pair<IdType, int>> AlreadyVisited;
for (auto &&EndLaneWaypoint : MapLaneBeginWaypoint) for (auto &&EndLaneWaypoint : MapLaneBeginWaypoint)
{ {
std::vector<Waypoint> Successors = WaypointGen::GetSuccessors(EndLaneWaypoint); std::vector<Waypoint> Successors = WaypointGen::GetSuccessors(EndLaneWaypoint);
// generate the RoutePlanner // The RoutePlanner will be created only if some route must be added to it
ARoutePlanner *RoutePlanner = GetWorld()->SpawnActor<ARoutePlanner>(); // so no one will be created unnecessarily
RoutePlanner->bIsIntersection = std::any_of(Successors.begin(), Successors.end(), [](auto w) { ARoutePlanner *RoutePlanner = nullptr;
return w.IsIntersection();
});
RoutePlanner->SetBoxExtent(FVector(70.f, 70.f, 50.f));
RoutePlanner->SetActorRotation(EndLaneWaypoint.ComputeTransform().rotation);
RoutePlanner->SetActorLocation(EndLaneWaypoint.ComputeTransform().location +
FVector(0.f, 0.f, TriggersHeight));
// fill the RoutePlanner with all the needed roads // Fill the RoutePlanner with all the needed roads
for (auto &&Successor : Successors) for (auto &&Successor : Successors)
{ {
const IdType RoadId = Successor.GetRoadId(); const IdType RoadId = Successor.GetRoadId();
const float MaxDist = map.GetRoad(RoadId)->GetLength(); const int LaneId = Successor.GetLaneId();
std::vector<Waypoint> Waypoints; // Create an identifier of the current lane
const auto Identifier = std::make_pair(RoadId, LaneId);
Waypoints.emplace_back(Successor); // If Identifier does not exist in AlreadyVisited we haven't visited the lane
if (!std::any_of(AlreadyVisited.begin(), AlreadyVisited.end(), [&Identifier](auto i) {
for (float Dist = RoadAccuracy; Dist < MaxDist; Dist += RoadAccuracy) return (i.first == Identifier.first && i.second == Identifier.second);
}))
{ {
const auto NewWaypoint = WaypointGen::GetNext(Successor, Dist); // Add the identifier as visited
AlreadyVisited.emplace_back(Identifier);
check(Dist < MaxDist); const float MaxDist = map.GetRoad(RoadId)->GetLength();
check(NewWaypoint.size() == 1);
Waypoints.emplace_back(NewWaypoint[0]); std::vector<Waypoint> Waypoints;
Waypoints.emplace_back(Successor);
for (float Dist = RoadAccuracy; Dist < MaxDist; Dist += RoadAccuracy)
{
const auto NewWaypoint = WaypointGen::GetNext(Successor, Dist);
check(Dist < MaxDist);
check(NewWaypoint.size() == 1);
Waypoints.emplace_back(NewWaypoint[0]);
}
// Merge with the first waypoint of the next lane if needed
Waypoints.emplace_back(WaypointGen::GetNext(
Successor, CarlaMath::clamp(MaxDist - 0.1f, 0.f, MaxDist))[0]);
check(Waypoints.size() >= 2);
TArray<FVector> Positions = WaypointVector2FVectorArray(Waypoints, TriggersHeight);
// If the route planner does not exist, create it
if (RoutePlanner == nullptr)
{
RoutePlanner = GetWorld()->SpawnActor<ARoutePlanner>();
RoutePlanner->bIsIntersection = std::any_of(Successors.begin(), Successors.end(), [](auto w) {
return w.IsIntersection();
});
RoutePlanner->SetBoxExtent(FVector(70.f, 70.f, 50.f));
RoutePlanner->SetActorRotation(EndLaneWaypoint.ComputeTransform().rotation);
RoutePlanner->SetActorLocation(EndLaneWaypoint.ComputeTransform().location +
FVector(0.f, 0.f, TriggersHeight));
}
RoutePlanner->AddRoute(1.f, Positions);
RoutePlanners.Add(RoutePlanner);
} }
// merge with the first waypoint of the next lane if needed
Waypoints.emplace_back(WaypointGen::GetNext(
Successor, CarlaMath::clamp(MaxDist - 0.1f, 0.f, MaxDist))[0]);
check(Waypoints.size() >= 2);
TArray<FVector> Positions = WaypointVector2FVectorArray(Waypoints, TriggersHeight);
RoutePlanner->AddRoute(1.f, Positions);
RoutePlanners.Add(RoutePlanner);
} }
} }
} }

View File

@ -0,0 +1,154 @@
// 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/Sensor/ObstacleDetectionSensor.h"
#include "Carla/Actor/ActorBlueprintFunctionLibrary.h"
#include "Carla/Actor/ActorRegistry.h"
#include "Carla/Game/CarlaEpisode.h"
#include "Carla/Game/CarlaGameInstance.h"
#include "Carla/Game/TheNewCarlaGameModeBase.h"
AObstacleDetectionSensor::AObstacleDetectionSensor(const FObjectInitializer &ObjectInitializer)
: Super(ObjectInitializer)
{
PrimaryActorTick.bCanEverTick = true;
}
FActorDefinition AObstacleDetectionSensor::GetSensorDefinition()
{
FActorDefinition SensorDefinition = FActorDefinition();
UActorBlueprintFunctionLibrary::MakeObstacleDetectorDefinitions(TEXT("other"), TEXT("obstacle"), SensorDefinition);
return SensorDefinition;
}
void AObstacleDetectionSensor::Set(const FActorDescription &Description)
{
//Multiplying numbers for 100 in order to convert from meters to centimeters
Super::Set(Description);
Distance = UActorBlueprintFunctionLibrary::RetrieveActorAttributeToFloat(
"distance",
Description.Variations,
Distance) * 100.0f;
HitRadius = UActorBlueprintFunctionLibrary::RetrieveActorAttributeToFloat(
"hit_radius",
Description.Variations,
HitRadius) * 100.0f;
bOnlyDynamics = UActorBlueprintFunctionLibrary::RetrieveActorAttributeToBool(
"only_dynamics",
Description.Variations,
bOnlyDynamics);
bDebugLineTrace = UActorBlueprintFunctionLibrary::RetrieveActorAttributeToBool(
"debug_linetrace",
Description.Variations,
bDebugLineTrace);
}
void AObstacleDetectionSensor::BeginPlay()
{
Super::BeginPlay();
auto *GameMode = Cast<ATheNewCarlaGameModeBase>(GetWorld()->GetAuthGameMode());
if (GameMode == nullptr)
{
UE_LOG(LogCarla, Error, TEXT("AObstacleDetectionSensor: Game mode not compatible with this sensor"));
return;
}
Episode = &GameMode->GetCarlaEpisode();
}
void AObstacleDetectionSensor::Tick(float DeltaSeconds)
{
Super::Tick(DeltaSeconds);
const FVector &Start = GetActorLocation();
const FVector &End = Start + (GetActorForwardVector() * Distance);
UWorld* currentWorld = GetWorld();
// Struct in which the result of the scan will be saved
FHitResult HitOut = FHitResult();
// Initialization of Query Parameters
FCollisionQueryParams TraceParams(FName(TEXT("ObstacleDetection Trace")), true, this);
// If debug mode enabled, we create a tag that will make the sweep be
// displayed.
if (bDebugLineTrace)
{
const FName TraceTag("ObstacleDebugTrace");
currentWorld->DebugDrawTraceTag = TraceTag;
TraceParams.TraceTag = TraceTag;
}
// Hit against complex meshes
TraceParams.bTraceComplex = true;
// Ignore trigger boxes
TraceParams.bIgnoreTouches = true;
// Limit the returned information
TraceParams.bReturnPhysicalMaterial = false;
// Ignore ourselves
TraceParams.AddIgnoredActor(this);
if(Super::GetOwner()!=nullptr)
TraceParams.AddIgnoredActor(Super::GetOwner());
bool isHitReturned;
// Choosing a type of sweep is a workaround until everything get properly
// organized under correct collision channels and object types.
if (bOnlyDynamics)
{
// If we go only for dynamics, we check the object type AllDynamicObjects
FCollisionObjectQueryParams TraceChannel = FCollisionObjectQueryParams(
FCollisionObjectQueryParams::AllDynamicObjects);
isHitReturned = currentWorld->SweepSingleByObjectType(
HitOut,
Start,
End,
FQuat(),
TraceChannel,
FCollisionShape::MakeSphere(HitRadius),
TraceParams);
}
else
{
// Else, if we go for everything, we get everything that interacts with a
// Pawn
ECollisionChannel TraceChannel = ECC_WorldStatic;
isHitReturned = currentWorld->SweepSingleByChannel(
HitOut,
Start,
End,
FQuat(),
TraceChannel,
FCollisionShape::MakeSphere(HitRadius),
TraceParams);
}
if (isHitReturned)
{
OnObstacleDetectionEvent(this, HitOut.Actor.Get(), HitOut.Distance, HitOut);
}
}
void AObstacleDetectionSensor::OnObstacleDetectionEvent(
AActor *Actor,
AActor *OtherActor,
float HitDistance,
const FHitResult &Hit)
{
if ((Episode != nullptr) && (Actor != nullptr) && (OtherActor != nullptr))
{
GetDataStream(*this).Send(*this,
Episode->SerializeActor(Episode->FindOrFakeActor(Actor)),
Episode->SerializeActor(Episode->FindOrFakeActor(OtherActor)),
HitRadius);
}
}

View File

@ -0,0 +1,56 @@
// 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/Sensor/Sensor.h"
#include "Carla/Actor/ActorDefinition.h"
#include "Carla/Actor/ActorDescription.h"
#include "ObstacleDetectionSensor.generated.h"
class UCarlaEpisode;
/// A sensor to register collisions.
UCLASS()
class CARLA_API AObstacleDetectionSensor : public ASensor
{
GENERATED_BODY()
public:
static FActorDefinition GetSensorDefinition();
AObstacleDetectionSensor(const FObjectInitializer &ObjectInitializer);
void Set(const FActorDescription &Description) override;
void BeginPlay() override;
void Tick(float DeltaSeconds) override;
private:
UFUNCTION()
void OnObstacleDetectionEvent(
AActor *Actor,
AActor *OtherActor,
float Distance,
const FHitResult &Hit);
UPROPERTY()
const UCarlaEpisode *Episode = nullptr;
private:
float Distance;
float HitRadius;
bool bOnlyDynamics = false;
bool bDebugLineTrace = false;
};

View File

@ -17,7 +17,7 @@
#include <carla/sensor/data/ActorDynamicState.h> #include <carla/sensor/data/ActorDynamicState.h>
#include <compiler/enable-ue4-macros.h> #include <compiler/enable-ue4-macros.h>
static auto AWorldObserver_GetActorState(const FActorView &View) static auto AWorldObserver_GetActorState(const FActorView &View, const FActorRegistry &Registry)
{ {
using AType = FActorView::ActorType; using AType = FActorView::ActorType;
@ -28,9 +28,28 @@ static auto AWorldObserver_GetActorState(const FActorView &View)
auto Vehicle = Cast<ACarlaWheeledVehicle>(View.GetActor()); auto Vehicle = Cast<ACarlaWheeledVehicle>(View.GetActor());
if (Vehicle != nullptr) if (Vehicle != nullptr)
{ {
state.vehicle_control = carla::rpc::VehicleControl{Vehicle->GetVehicleControl()}; state.vehicle_data.control = carla::rpc::VehicleControl{Vehicle->GetVehicleControl()};
auto Controller = Cast<AWheeledVehicleAIController>(Vehicle->GetController());
if (Controller != nullptr)
{
using TLS = carla::rpc::TrafficLightState;
state.vehicle_data.traffic_light_state = static_cast<TLS>(Controller->GetTrafficLightState());
state.vehicle_data.speed_limit = Controller->GetSpeedLimit();
auto TrafficLight = Controller->GetTrafficLight();
if (TrafficLight != nullptr)
{
state.vehicle_data.has_traffic_light = true;
auto TrafficLightView = Registry.Find(TrafficLight);
state.vehicle_data.traffic_light_id = TrafficLightView.GetActorId();
}
else
{
state.vehicle_data.has_traffic_light = false;
}
}
} }
} }
else if (AType::Walker == View.GetActorType()) else if (AType::Walker == View.GetActorType())
{ {
auto Walker = Cast<APawn>(View.GetActor()); auto Walker = Cast<APawn>(View.GetActor());
@ -46,7 +65,12 @@ static auto AWorldObserver_GetActorState(const FActorView &View)
if (TrafficLight != nullptr) if (TrafficLight != nullptr)
{ {
using TLS = carla::rpc::TrafficLightState; using TLS = carla::rpc::TrafficLightState;
state.traffic_light_state = static_cast<TLS>(TrafficLight->GetTrafficSignState()); state.traffic_light_data.state = static_cast<TLS>(TrafficLight->GetTrafficLightState());
state.traffic_light_data.green_time = TrafficLight->GetGreenTime();
state.traffic_light_data.yellow_time = TrafficLight->GetYellowTime();
state.traffic_light_data.red_time = TrafficLight->GetRedTime();
state.traffic_light_data.elapsed_time = TrafficLight->GetElapsedTime();
state.traffic_light_data.time_is_frozen = TrafficLight->GetTimeIsFrozen();
} }
} }
@ -75,7 +99,8 @@ static carla::Buffer AWorldObserver_Serialize(
write_data(header); write_data(header);
// Write every actor. // Write every actor.
for (auto &&View : Registry) { for (auto &&View : Registry)
{
check(View.IsValid()); check(View.IsValid());
constexpr float TO_METERS = 1e-2; constexpr float TO_METERS = 1e-2;
const auto velocity = TO_METERS * View.GetActor()->GetVelocity(); const auto velocity = TO_METERS * View.GetActor()->GetVelocity();
@ -83,13 +108,15 @@ static carla::Buffer AWorldObserver_Serialize(
const auto RootComponent = Cast<UPrimitiveComponent>(View.GetActor()->GetRootComponent()); const auto RootComponent = Cast<UPrimitiveComponent>(View.GetActor()->GetRootComponent());
FVector angularVelocity { 0.0f, 0.0f, 0.0f }; FVector angularVelocity { 0.0f, 0.0f, 0.0f };
if (RootComponent != nullptr) if (RootComponent != nullptr)
angularVelocity = RootComponent->GetPhysicsAngularVelocityInDegrees(); {
angularVelocity = RootComponent->GetPhysicsAngularVelocityInDegrees();
}
ActorDynamicState info = { ActorDynamicState info = {
View.GetActorId(), View.GetActorId(),
View.GetActor()->GetActorTransform(), View.GetActor()->GetActorTransform(),
carla::geom::Vector3D{velocity.X, velocity.Y, velocity.Z}, carla::geom::Vector3D{velocity.X, velocity.Y, velocity.Z},
carla::geom::Vector3D{angularVelocity.X, angularVelocity.Y, angularVelocity.Z}, carla::geom::Vector3D{angularVelocity.X, angularVelocity.Y, angularVelocity.Z},
AWorldObserver_GetActorState(View) AWorldObserver_GetActorState(View, Registry)
}; };
write_data(info); write_data(info);
} }
@ -98,7 +125,7 @@ static carla::Buffer AWorldObserver_Serialize(
return buffer; return buffer;
} }
AWorldObserver::AWorldObserver(const FObjectInitializer& ObjectInitializer) AWorldObserver::AWorldObserver(const FObjectInitializer &ObjectInitializer)
: Super(ObjectInitializer) : Super(ObjectInitializer)
{ {
PrimaryActorTick.bCanEverTick = true; PrimaryActorTick.bCanEverTick = true;
@ -119,6 +146,5 @@ void AWorldObserver::Tick(float DeltaSeconds)
GameTimeStamp, GameTimeStamp,
FPlatformTime::Seconds(), FPlatformTime::Seconds(),
Episode->GetActorRegistry()); Episode->GetActorRegistry());
AsyncStream.Send(*this, std::move(buffer)); AsyncStream.Send(*this, std::move(buffer));
} }

View File

@ -55,7 +55,8 @@ public:
FPimpl(uint16_t port) FPimpl(uint16_t port)
: Server(port), : Server(port),
StreamingServer(port + 1u) { StreamingServer(port + 1u)
{
BindActions(); BindActions();
} }
@ -68,6 +69,7 @@ public:
private: private:
void BindActions(); void BindActions();
}; };
// ============================================================================= // =============================================================================
@ -80,17 +82,17 @@ private:
# define CARLA_ENSURE_GAME_THREAD() # define CARLA_ENSURE_GAME_THREAD()
#endif // WITH_EDITOR #endif // WITH_EDITOR
#define RESPOND_ERROR(str) { \ #define RESPOND_ERROR(str) { \
UE_LOG(LogCarlaServer, Log, TEXT("Responding error: %s"), TEXT(str)); \ UE_LOG(LogCarlaServer, Log, TEXT("Responding error: %s"), TEXT(str)); \
return carla::rpc::ResponseError(str); } return carla::rpc::ResponseError(str); }
#define RESPOND_ERROR_FSTRING(fstr) { \ #define RESPOND_ERROR_FSTRING(fstr) { \
UE_LOG(LogCarlaServer, Log, TEXT("Responding error: %s"), *fstr); \ UE_LOG(LogCarlaServer, Log, TEXT("Responding error: %s"), *fstr); \
return carla::rpc::ResponseError(carla::rpc::FromFString(fstr)); } return carla::rpc::ResponseError(carla::rpc::FromFString(fstr)); }
#define REQUIRE_CARLA_EPISODE() \ #define REQUIRE_CARLA_EPISODE() \
CARLA_ENSURE_GAME_THREAD(); \ CARLA_ENSURE_GAME_THREAD(); \
if (Episode == nullptr) { RESPOND_ERROR("episode not ready"); } if (Episode == nullptr) { RESPOND_ERROR("episode not ready"); }
// ============================================================================= // =============================================================================
// -- Bind Actions ------------------------------------------------------------- // -- Bind Actions -------------------------------------------------------------
@ -110,13 +112,14 @@ void FTheNewCarlaServer::FPimpl::BindActions()
{ {
REQUIRE_CARLA_EPISODE(); REQUIRE_CARLA_EPISODE();
auto WorldObserver = Episode->GetWorldObserver(); auto WorldObserver = Episode->GetWorldObserver();
if (WorldObserver == nullptr) { if (WorldObserver == nullptr)
{
RESPOND_ERROR("internal error: missing world observer"); RESPOND_ERROR("internal error: missing world observer");
} }
return cr::EpisodeInfo{ return cr::EpisodeInfo{
Episode->GetId(), Episode->GetId(),
cr::FromFString(Episode->GetMapName()), cr::FromFString(Episode->GetMapName()),
WorldObserver->GetToken()}; WorldObserver->GetToken()};
}); });
Server.BindSync("get_map_info", [this]() -> R<cr::MapInfo> Server.BindSync("get_map_info", [this]() -> R<cr::MapInfo>
@ -125,9 +128,9 @@ void FTheNewCarlaServer::FPimpl::BindActions()
auto FileContents = FOpenDrive::Load(Episode->GetMapName()); auto FileContents = FOpenDrive::Load(Episode->GetMapName());
const auto &SpawnPoints = Episode->GetRecommendedSpawnPoints(); const auto &SpawnPoints = Episode->GetRecommendedSpawnPoints();
return cr::MapInfo{ return cr::MapInfo{
cr::FromFString(Episode->GetMapName()), cr::FromFString(Episode->GetMapName()),
cr::FromFString(FileContents), cr::FromFString(FileContents),
MakeVectorFromTArray<cg::Transform>(SpawnPoints)}; MakeVectorFromTArray<cg::Transform>(SpawnPoints)};
}); });
Server.BindSync("get_actor_definitions", [this]() -> R<std::vector<cr::ActorDefinition>> Server.BindSync("get_actor_definitions", [this]() -> R<std::vector<cr::ActorDefinition>>
@ -158,7 +161,7 @@ void FTheNewCarlaServer::FPimpl::BindActions()
}); });
Server.BindSync("set_weather_parameters", [this]( Server.BindSync("set_weather_parameters", [this](
const cr::WeatherParameters &weather) -> R<void> const cr::WeatherParameters &weather) -> R<void>
{ {
REQUIRE_CARLA_EPISODE(); REQUIRE_CARLA_EPISODE();
auto *Weather = Episode->GetWeather(); auto *Weather = Episode->GetWeather();
@ -171,7 +174,7 @@ void FTheNewCarlaServer::FPimpl::BindActions()
}); });
Server.BindSync("get_actors_by_id", [this]( Server.BindSync("get_actors_by_id", [this](
const std::vector<FActorView::IdType> &ids) -> R<std::vector<cr::Actor>> const std::vector<FActorView::IdType> &ids) -> R<std::vector<cr::Actor>>
{ {
REQUIRE_CARLA_EPISODE(); REQUIRE_CARLA_EPISODE();
std::vector<cr::Actor> Result; std::vector<cr::Actor> Result;
@ -188,8 +191,8 @@ void FTheNewCarlaServer::FPimpl::BindActions()
}); });
Server.BindSync("spawn_actor", [this]( Server.BindSync("spawn_actor", [this](
cr::ActorDescription Description, cr::ActorDescription Description,
const cr::Transform &Transform) -> R<cr::Actor> const cr::Transform &Transform) -> R<cr::Actor>
{ {
REQUIRE_CARLA_EPISODE(); REQUIRE_CARLA_EPISODE();
auto Result = Episode->SpawnActorWithInfo(Transform, std::move(Description)); auto Result = Episode->SpawnActorWithInfo(Transform, std::move(Description));
@ -205,9 +208,9 @@ void FTheNewCarlaServer::FPimpl::BindActions()
}); });
Server.BindSync("spawn_actor_with_parent", [this]( Server.BindSync("spawn_actor_with_parent", [this](
cr::ActorDescription Description, cr::ActorDescription Description,
const cr::Transform &Transform, const cr::Transform &Transform,
cr::Actor Parent) -> R<cr::Actor> cr::Actor Parent) -> R<cr::Actor>
{ {
REQUIRE_CARLA_EPISODE(); REQUIRE_CARLA_EPISODE();
auto Result = Episode->SpawnActorWithInfo(Transform, std::move(Description)); auto Result = Episode->SpawnActorWithInfo(Transform, std::move(Description));
@ -244,8 +247,8 @@ void FTheNewCarlaServer::FPimpl::BindActions()
}); });
Server.BindSync("attach_actors", [this]( Server.BindSync("attach_actors", [this](
cr::Actor Child, cr::Actor Child,
cr::Actor Parent) -> R<void> cr::Actor Parent) -> R<void>
{ {
REQUIRE_CARLA_EPISODE(); REQUIRE_CARLA_EPISODE();
auto ChildView = Episode->FindActor(Child.id); auto ChildView = Episode->FindActor(Child.id);
@ -263,8 +266,8 @@ void FTheNewCarlaServer::FPimpl::BindActions()
}); });
Server.BindSync("set_actor_location", [this]( Server.BindSync("set_actor_location", [this](
cr::Actor Actor, cr::Actor Actor,
cr::Location Location) -> R<void> cr::Location Location) -> R<void>
{ {
REQUIRE_CARLA_EPISODE(); REQUIRE_CARLA_EPISODE();
auto ActorView = Episode->FindActor(Actor.id); auto ActorView = Episode->FindActor(Actor.id);
@ -273,16 +276,16 @@ void FTheNewCarlaServer::FPimpl::BindActions()
RESPOND_ERROR("unable to set actor location: actor not found"); RESPOND_ERROR("unable to set actor location: actor not found");
} }
ActorView.GetActor()->SetActorRelativeLocation( ActorView.GetActor()->SetActorRelativeLocation(
Location, Location,
false, false,
nullptr, nullptr,
ETeleportType::TeleportPhysics); ETeleportType::TeleportPhysics);
return R<void>::Success(); return R<void>::Success();
}); });
Server.BindSync("set_actor_transform", [this]( Server.BindSync("set_actor_transform", [this](
cr::Actor Actor, cr::Actor Actor,
cr::Transform Transform) -> R<void> cr::Transform Transform) -> R<void>
{ {
REQUIRE_CARLA_EPISODE(); REQUIRE_CARLA_EPISODE();
auto ActorView = Episode->FindActor(Actor.id); auto ActorView = Episode->FindActor(Actor.id);
@ -291,16 +294,16 @@ void FTheNewCarlaServer::FPimpl::BindActions()
RESPOND_ERROR("unable to set actor transform: actor not found"); RESPOND_ERROR("unable to set actor transform: actor not found");
} }
ActorView.GetActor()->SetActorRelativeTransform( ActorView.GetActor()->SetActorRelativeTransform(
Transform, Transform,
false, false,
nullptr, nullptr,
ETeleportType::TeleportPhysics); ETeleportType::TeleportPhysics);
return R<void>::Success(); return R<void>::Success();
}); });
Server.BindSync("set_actor_velocity", [this]( Server.BindSync("set_actor_velocity", [this](
cr::Actor Actor, cr::Actor Actor,
cr::Vector3D vector) -> R<void> cr::Vector3D vector) -> R<void>
{ {
REQUIRE_CARLA_EPISODE(); REQUIRE_CARLA_EPISODE();
auto ActorView = Episode->FindActor(Actor.id); auto ActorView = Episode->FindActor(Actor.id);
@ -314,15 +317,15 @@ void FTheNewCarlaServer::FPimpl::BindActions()
RESPOND_ERROR("unable to set actor velocity: not supported by actor"); RESPOND_ERROR("unable to set actor velocity: not supported by actor");
} }
RootComponent->SetPhysicsLinearVelocity( RootComponent->SetPhysicsLinearVelocity(
vector.ToCentimeters(), vector.ToCentimeters(),
false, false,
"None"); "None");
return R<void>::Success(); return R<void>::Success();
}); });
Server.BindSync("set_actor_angular_velocity", [this]( Server.BindSync("set_actor_angular_velocity", [this](
cr::Actor Actor, cr::Actor Actor,
cr::Vector3D vector) -> R<void> cr::Vector3D vector) -> R<void>
{ {
REQUIRE_CARLA_EPISODE(); REQUIRE_CARLA_EPISODE();
auto ActorView = Episode->FindActor(Actor.id); auto ActorView = Episode->FindActor(Actor.id);
@ -336,15 +339,15 @@ void FTheNewCarlaServer::FPimpl::BindActions()
RESPOND_ERROR("unable to set actor angular velocity: not supported by actor"); RESPOND_ERROR("unable to set actor angular velocity: not supported by actor");
} }
RootComponent->SetPhysicsAngularVelocityInDegrees( RootComponent->SetPhysicsAngularVelocityInDegrees(
vector, vector,
false, false,
"None"); "None");
return R<void>::Success(); return R<void>::Success();
}); });
Server.BindSync("add_actor_impulse", [this]( Server.BindSync("add_actor_impulse", [this](
cr::Actor Actor, cr::Actor Actor,
cr::Vector3D vector) -> R<void> cr::Vector3D vector) -> R<void>
{ {
REQUIRE_CARLA_EPISODE(); REQUIRE_CARLA_EPISODE();
auto ActorView = Episode->FindActor(Actor.id); auto ActorView = Episode->FindActor(Actor.id);
@ -358,15 +361,15 @@ void FTheNewCarlaServer::FPimpl::BindActions()
RESPOND_ERROR("unable to add actor impulse: not supported by actor"); RESPOND_ERROR("unable to add actor impulse: not supported by actor");
} }
RootComponent->AddImpulse( RootComponent->AddImpulse(
vector.ToCentimeters(), vector.ToCentimeters(),
"None", "None",
false); false);
return R<void>::Success(); return R<void>::Success();
}); });
Server.BindSync("set_actor_simulate_physics", [this]( Server.BindSync("set_actor_simulate_physics", [this](
cr::Actor Actor, cr::Actor Actor,
bool bEnabled) -> R<void> bool bEnabled) -> R<void>
{ {
REQUIRE_CARLA_EPISODE(); REQUIRE_CARLA_EPISODE();
auto ActorView = Episode->FindActor(Actor.id); auto ActorView = Episode->FindActor(Actor.id);
@ -384,8 +387,8 @@ void FTheNewCarlaServer::FPimpl::BindActions()
}); });
Server.BindSync("apply_control_to_vehicle", [this]( Server.BindSync("apply_control_to_vehicle", [this](
cr::Actor Actor, cr::Actor Actor,
cr::VehicleControl Control) -> R<void> cr::VehicleControl Control) -> R<void>
{ {
REQUIRE_CARLA_EPISODE(); REQUIRE_CARLA_EPISODE();
auto ActorView = Episode->FindActor(Actor.id); auto ActorView = Episode->FindActor(Actor.id);
@ -403,8 +406,8 @@ void FTheNewCarlaServer::FPimpl::BindActions()
}); });
Server.BindSync("apply_control_to_walker", [this]( Server.BindSync("apply_control_to_walker", [this](
cr::Actor Actor, cr::Actor Actor,
cr::WalkerControl Control) -> R<void> cr::WalkerControl Control) -> R<void>
{ {
REQUIRE_CARLA_EPISODE(); REQUIRE_CARLA_EPISODE();
auto ActorView = Episode->FindActor(Actor.id); auto ActorView = Episode->FindActor(Actor.id);
@ -427,8 +430,8 @@ void FTheNewCarlaServer::FPimpl::BindActions()
}); });
Server.BindSync("set_actor_autopilot", [this]( Server.BindSync("set_actor_autopilot", [this](
cr::Actor Actor, cr::Actor Actor,
bool bEnabled) -> R<void> bool bEnabled) -> R<void>
{ {
REQUIRE_CARLA_EPISODE(); REQUIRE_CARLA_EPISODE();
auto ActorView = Episode->FindActor(Actor.id); auto ActorView = Episode->FindActor(Actor.id);
@ -450,6 +453,101 @@ void FTheNewCarlaServer::FPimpl::BindActions()
return R<void>::Success(); return R<void>::Success();
}); });
Server.BindSync("set_traffic_light_state", [this](
cr::Actor Actor,
cr::TrafficLightState trafficLightState) -> R<void>
{
REQUIRE_CARLA_EPISODE();
auto ActorView = Episode->GetActorRegistry().Find(Actor.id);
if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill())
{
RESPOND_ERROR("unable to set state: actor not found");
}
auto TrafficLight = Cast<ATrafficLightBase>(ActorView.GetActor());
if (TrafficLight == nullptr)
{
RESPOND_ERROR("unable to set state: actor is not a traffic light");
}
TrafficLight->SetTrafficLightState(static_cast<ETrafficLightState>(trafficLightState));
return R<void>::Success();
});
Server.BindSync("set_traffic_light_green_time", [this](
cr::Actor Actor,
float GreenTime) -> R<void>
{
REQUIRE_CARLA_EPISODE();
auto ActorView = Episode->GetActorRegistry().Find(Actor.id);
if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill())
{
RESPOND_ERROR("unable to set green time: actor not found");
}
auto TrafficLight = Cast<ATrafficLightBase>(ActorView.GetActor());
if (TrafficLight == nullptr)
{
RESPOND_ERROR("unable to set green time: actor is not a traffic light");
}
TrafficLight->SetGreenTime(GreenTime);
return R<void>::Success();
});
Server.BindSync("set_traffic_light_yellow_time", [this](
cr::Actor Actor,
float YellowTime) -> R<void>
{
REQUIRE_CARLA_EPISODE();
auto ActorView = Episode->GetActorRegistry().Find(Actor.id);
if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill())
{
RESPOND_ERROR("unable to set yellow time: actor not found");
}
auto TrafficLight = Cast<ATrafficLightBase>(ActorView.GetActor());
if (TrafficLight == nullptr)
{
RESPOND_ERROR("unable to set yellow time: actor is not a traffic light");
}
TrafficLight->SetYellowTime(YellowTime);
return R<void>::Success();
});
Server.BindSync("set_traffic_light_red_time", [this](
cr::Actor Actor,
float RedTime) -> R<void>
{
REQUIRE_CARLA_EPISODE();
auto ActorView = Episode->GetActorRegistry().Find(Actor.id);
if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill())
{
RESPOND_ERROR("unable to set red time: actor not found");
}
auto TrafficLight = Cast<ATrafficLightBase>(ActorView.GetActor());
if (TrafficLight == nullptr)
{
RESPOND_ERROR("unable to set red time: actor is not a traffic light");
}
TrafficLight->SetRedTime(RedTime);
return R<void>::Success();
});
Server.BindSync("freeze_traffic_light", [this](
cr::Actor Actor,
bool Freeze) -> R<void>
{
REQUIRE_CARLA_EPISODE();
auto ActorView = Episode->GetActorRegistry().Find(Actor.id);
if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill())
{
RESPOND_ERROR("unable to alter frozen state: actor not found");
}
auto TrafficLight = Cast<ATrafficLightBase>(ActorView.GetActor());
if (TrafficLight == nullptr)
{
RESPOND_ERROR("unable to alter frozen state: actor is not a traffic light");
}
TrafficLight->SetTimeIsFrozen(Freeze);
return R<void>::Success();
});
Server.BindSync("draw_debug_shape", [this](const cr::DebugShape &shape) -> R<void> Server.BindSync("draw_debug_shape", [this](const cr::DebugShape &shape) -> R<void>
{ {
REQUIRE_CARLA_EPISODE(); REQUIRE_CARLA_EPISODE();

View File

@ -19,8 +19,10 @@ static bool IsValid(const ACarlaWheeledVehicle *Vehicle)
return ((Vehicle != nullptr) && !Vehicle->IsPendingKill()); return ((Vehicle != nullptr) && !Vehicle->IsPendingKill());
} }
static ETrafficSignState ToTrafficSignState(ETrafficLightState State) { static ETrafficSignState ToTrafficSignState(ETrafficLightState State)
switch (State) { {
switch (State)
{
case ETrafficLightState::Green: case ETrafficLightState::Green:
return ETrafficSignState::TrafficLightGreen; return ETrafficSignState::TrafficLightGreen;
case ETrafficLightState::Yellow: case ETrafficLightState::Yellow:
@ -38,7 +40,7 @@ static ETrafficSignState ToTrafficSignState(ETrafficLightState State) {
ATrafficLightBase::ATrafficLightBase(const FObjectInitializer &ObjectInitializer) ATrafficLightBase::ATrafficLightBase(const FObjectInitializer &ObjectInitializer)
: Super(ObjectInitializer) : Super(ObjectInitializer)
{ {
PrimaryActorTick.bCanEverTick = false; PrimaryActorTick.bCanEverTick = true;
} }
void ATrafficLightBase::OnConstruction(const FTransform &Transform) void ATrafficLightBase::OnConstruction(const FTransform &Transform)
@ -47,13 +49,48 @@ void ATrafficLightBase::OnConstruction(const FTransform &Transform)
SetTrafficLightState(State); SetTrafficLightState(State);
} }
void ATrafficLightBase::Tick(float DeltaSeconds)
{
if (TimeIsFrozen)
{
return;
}
ElapsedTime += DeltaSeconds;
float ChangeTime;
switch (State)
{
case ETrafficLightState::Red:
ChangeTime = RedTime;
break;
case ETrafficLightState::Yellow:
ChangeTime = YellowTime;
break;
case ETrafficLightState::Green:
ChangeTime = GreenTime;
break;
default:
UE_LOG(LogCarla, Error, TEXT("Invalid traffic light state!"));
SetTrafficLightState(ETrafficLightState::Red);
return;
}
if (ElapsedTime > ChangeTime)
{
SwitchTrafficLightState();
}
}
#if WITH_EDITOR #if WITH_EDITOR
void ATrafficLightBase::PostEditChangeProperty(FPropertyChangedEvent &Event) void ATrafficLightBase::PostEditChangeProperty(FPropertyChangedEvent &Event)
{ {
Super::PostEditChangeProperty(Event); Super::PostEditChangeProperty(Event);
const FName PropertyName = (Event.Property != nullptr ? Event.Property->GetFName() : NAME_None); const FName PropertyName = (Event.Property != nullptr ? Event.Property->GetFName() : NAME_None);
if (PropertyName == GET_MEMBER_NAME_CHECKED(ATrafficLightBase, State)) { if (PropertyName == GET_MEMBER_NAME_CHECKED(ATrafficLightBase, State))
{
SetTrafficLightState(State); SetTrafficLightState(State);
} }
} }
@ -61,14 +98,23 @@ void ATrafficLightBase::PostEditChangeProperty(FPropertyChangedEvent &Event)
void ATrafficLightBase::SetTrafficLightState(const ETrafficLightState InState) void ATrafficLightBase::SetTrafficLightState(const ETrafficLightState InState)
{ {
NumChanges++;
ElapsedTime = 0.0f;
State = InState; State = InState;
SetTrafficSignState(ToTrafficSignState(State)); SetTrafficSignState(ToTrafficSignState(State));
for (auto Controller : Vehicles) { for (auto Controller : Vehicles)
if (Controller != nullptr) { {
if (Controller != nullptr)
{
Controller->SetTrafficLightState(State); Controller->SetTrafficLightState(State);
if (State == ETrafficLightState::Green)
{
Controller->SetTrafficLight(nullptr);
}
} }
} }
if (State == ETrafficLightState::Green) { if (State == ETrafficLightState::Green)
{
Vehicles.Empty(); Vehicles.Empty();
} }
OnTrafficLightStateChanged(State); OnTrafficLightStateChanged(State);
@ -76,7 +122,8 @@ void ATrafficLightBase::SetTrafficLightState(const ETrafficLightState InState)
void ATrafficLightBase::SwitchTrafficLightState() void ATrafficLightBase::SwitchTrafficLightState()
{ {
switch (State) { switch (State)
{
case ETrafficLightState::Red: case ETrafficLightState::Red:
SetTrafficLightState(ETrafficLightState::Green); SetTrafficLightState(ETrafficLightState::Green);
break; break;
@ -95,13 +142,72 @@ void ATrafficLightBase::SwitchTrafficLightState()
void ATrafficLightBase::NotifyWheeledVehicle(ACarlaWheeledVehicle *Vehicle) void ATrafficLightBase::NotifyWheeledVehicle(ACarlaWheeledVehicle *Vehicle)
{ {
if (IsValid(Vehicle)) { if (IsValid(Vehicle))
{
auto Controller = Cast<AWheeledVehicleAIController>(Vehicle->GetController()); auto Controller = Cast<AWheeledVehicleAIController>(Vehicle->GetController());
if (Controller != nullptr) { if (Controller != nullptr)
{
Controller->SetTrafficLightState(State); Controller->SetTrafficLightState(State);
if (State != ETrafficLightState::Green) { if (State != ETrafficLightState::Green)
{
Vehicles.Add(Controller); Vehicles.Add(Controller);
Controller->SetTrafficLight(this);
} }
} }
} }
} }
void ATrafficLightBase::SetGreenTime(float InGreenTime)
{
GreenTime = InGreenTime;
}
float ATrafficLightBase::GetGreenTime() const
{
return GreenTime;
}
void ATrafficLightBase::SetYellowTime(float InYellowTime)
{
YellowTime = InYellowTime;
}
float ATrafficLightBase::GetYellowTime() const
{
return YellowTime;
}
void ATrafficLightBase::SetRedTime(float InRedTime)
{
RedTime = InRedTime;
}
float ATrafficLightBase::GetRedTime() const
{
return RedTime;
}
float ATrafficLightBase::GetElapsedTime() const
{
return ElapsedTime;
}
void ATrafficLightBase::SetTimeIsFrozen(bool InTimeIsFrozen)
{
TimeIsFrozen = InTimeIsFrozen;
if (!TimeIsFrozen)
{
NumChanges = 0;
ElapsedTime = 0.0f;
}
}
bool ATrafficLightBase::GetTimeIsFrozen() const
{
return TimeIsFrozen;
}
int ATrafficLightBase::GetNumChanges() const
{
return NumChanges;
}

View File

@ -16,7 +16,8 @@ class ACarlaWheeledVehicle;
class AWheeledVehicleAIController; class AWheeledVehicleAIController;
UCLASS() UCLASS()
class CARLA_API ATrafficLightBase : public ATrafficSignBase { class CARLA_API ATrafficLightBase : public ATrafficSignBase
{
GENERATED_BODY() GENERATED_BODY()
@ -24,12 +25,15 @@ public:
ATrafficLightBase(const FObjectInitializer &ObjectInitializer); ATrafficLightBase(const FObjectInitializer &ObjectInitializer);
virtual void Tick(float DeltaSeconds) override;
protected: protected:
virtual void OnConstruction(const FTransform &Transform) override; virtual void OnConstruction(const FTransform &Transform) override;
#if WITH_EDITOR #if WITH_EDITOR
virtual void PostEditChangeProperty(FPropertyChangedEvent &PropertyChangedEvent) override; virtual void PostEditChangeProperty(FPropertyChangedEvent &PropertyChangedEvent) override;
#endif // WITH_EDITOR #endif // WITH_EDITOR
public: public:
@ -50,6 +54,36 @@ public:
UFUNCTION(Category = "Traffic Light", BlueprintCallable) UFUNCTION(Category = "Traffic Light", BlueprintCallable)
void NotifyWheeledVehicle(ACarlaWheeledVehicle *Vehicle); void NotifyWheeledVehicle(ACarlaWheeledVehicle *Vehicle);
UFUNCTION(Category = "Traffic Light", BlueprintCallable)
void SetGreenTime(float InGreenTime);
UFUNCTION(Category = "Traffic Light", BlueprintCallable)
float GetGreenTime() const;
UFUNCTION(Category = "Traffic Light", BlueprintCallable)
void SetYellowTime(float InYellowTime);
UFUNCTION(Category = "Traffic Light", BlueprintCallable)
float GetYellowTime() const;
UFUNCTION(Category = "Traffic Light", BlueprintCallable)
void SetRedTime(float InRedTime);
UFUNCTION(Category = "Traffic Light", BlueprintCallable)
float GetRedTime() const;
UFUNCTION(Category = "Traffic Light", BlueprintCallable)
float GetElapsedTime() const;
UFUNCTION(Category = "Traffic Light", BlueprintCallable)
void SetTimeIsFrozen(bool InTimeIsFrozen);
UFUNCTION(Category = "Traffic Light", BlueprintCallable)
bool GetTimeIsFrozen() const;
UFUNCTION(Category = "Traffic Light", BlueprintCallable)
int GetNumChanges() const;
protected: protected:
UFUNCTION(Category = "Traffic Light", BlueprintImplementableEvent) UFUNCTION(Category = "Traffic Light", BlueprintImplementableEvent)
@ -62,4 +96,22 @@ private:
UPROPERTY(Category = "Traffic Light", VisibleAnywhere) UPROPERTY(Category = "Traffic Light", VisibleAnywhere)
TArray<AWheeledVehicleAIController *> Vehicles; TArray<AWheeledVehicleAIController *> Vehicles;
UPROPERTY(Category = "Traffic Light", EditAnywhere)
float GreenTime = 10.0f;
UPROPERTY(Category = "Traffic Light", EditAnywhere)
float YellowTime = 2.0f;
UPROPERTY(Category = "Traffic Light", EditAnywhere)
float RedTime = 7.0f;
UPROPERTY(Category = "Traffic Light", VisibleAnywhere)
float ElapsedTime = 0.0f;
UPROPERTY(Category = "Traffic Light", EditAnywhere)
bool TimeIsFrozen = false;
UPROPERTY(Category = "Traffic Light", VisibleAnywhere)
int NumChanges = 0;
}; };

View File

@ -11,11 +11,12 @@
/// State of a ACarlaWheeledVehicle, to be displayed in editor for debugging /// State of a ACarlaWheeledVehicle, to be displayed in editor for debugging
/// purposes. /// purposes.
UENUM(BlueprintType) UENUM(BlueprintType)
enum class ECarlaWheeledVehicleState : uint8 { enum class ECarlaWheeledVehicleState : uint8
AutopilotOff UMETA(DisplayName = "Autopilot Off"), {
FreeDriving UMETA(DisplayName = "Free driving"), AutopilotOff UMETA(DisplayName = "Autopilot Off"),
FollowingFixedRoute UMETA(DisplayName = "Following fixed route"), FreeDriving UMETA(DisplayName = "Free driving"),
WaitingForRedLight UMETA(DisplayName = "Waiting for red light"), FollowingFixedRoute UMETA(DisplayName = "Following fixed route"),
ObstacleAhead UMETA(DisplayName = "Obstacle ahead"), WaitingForRedLight UMETA(DisplayName = "Waiting for red light"),
UNKNOWN UMETA(DisplayName = "Unknown") ObstacleAhead UMETA(DisplayName = "Obstacle ahead"),
UNKNOWN UMETA(DisplayName = "Unknown")
}; };

View File

@ -18,18 +18,22 @@
// -- Static local methods ----------------------------------------------------- // -- Static local methods -----------------------------------------------------
// ============================================================================= // =============================================================================
static bool RayTrace(const AActor &Actor, const FVector &Start, const FVector &End) { static bool RayCast(const AActor &Actor, const FVector &Start, const FVector &End)
{
FHitResult OutHit; FHitResult OutHit;
static FName TraceTag = FName(TEXT("VehicleTrace")); static FName TraceTag = FName(TEXT("VehicleTrace"));
FCollisionQueryParams CollisionParams(TraceTag, true); FCollisionQueryParams CollisionParams(TraceTag, true);
CollisionParams.AddIgnoredActor(&Actor); CollisionParams.AddIgnoredActor(&Actor);
const bool Success = Actor.GetWorld()->LineTraceSingleByObjectType( const bool Success = Actor.GetWorld()->LineTraceSingleByObjectType(
OutHit, OutHit,
Start, Start,
End, End,
FCollisionObjectQueryParams(FCollisionObjectQueryParams::AllDynamicObjects), FCollisionObjectQueryParams(FCollisionObjectQueryParams::AllDynamicObjects),
CollisionParams); CollisionParams);
// DrawDebugLine(Actor.GetWorld(), Start, End,
// Success ? FColor(255, 0, 0) : FColor(0, 255, 0), false);
return Success && OutHit.bBlockingHit; return Success && OutHit.bBlockingHit;
} }
@ -42,21 +46,26 @@ static bool IsThereAnObstacleAhead(
const auto ForwardVector = Vehicle.GetVehicleOrientation(); const auto ForwardVector = Vehicle.GetVehicleOrientation();
const auto VehicleBounds = Vehicle.GetVehicleBoundingBoxExtent(); const auto VehicleBounds = Vehicle.GetVehicleBoundingBoxExtent();
FVector NormDirection = Direction.GetSafeNormal();
const float Distance = std::max(50.0f, Speed * Speed); // why? const float Distance = std::max(50.0f, Speed * Speed); // why?
const FVector StartCenter = Vehicle.GetActorLocation() + (ForwardVector * (250.0f + VehicleBounds.X / 2.0f)) + FVector(0.0f, 0.0f, 50.0f); const FVector StartCenter = Vehicle.GetActorLocation() +
const FVector EndCenter = StartCenter + Direction * (Distance + VehicleBounds.X / 2.0f); (ForwardVector * (250.0f + VehicleBounds.X / 2.0f)) + FVector(0.0f, 0.0f, 50.0f);
const FVector EndCenter = StartCenter + NormDirection * (Distance + VehicleBounds.X / 2.0f);
const FVector StartRight = StartCenter + (FVector(ForwardVector.Y, -ForwardVector.X, ForwardVector.Z) * 100.0f); const FVector StartRight = StartCenter +
const FVector EndRight = StartRight + Direction * (Distance + VehicleBounds.X / 2.0f); (FVector(ForwardVector.Y, -ForwardVector.X, ForwardVector.Z) * 100.0f);
const FVector EndRight = StartRight + NormDirection * (Distance + VehicleBounds.X / 2.0f);
const FVector StartLeft = StartCenter + (FVector(-ForwardVector.Y, ForwardVector.X, ForwardVector.Z) * 100.0f); const FVector StartLeft = StartCenter +
const FVector EndLeft = StartLeft + Direction * (Distance + VehicleBounds.X / 2.0f); (FVector(-ForwardVector.Y, ForwardVector.X, ForwardVector.Z) * 100.0f);
const FVector EndLeft = StartLeft + NormDirection * (Distance + VehicleBounds.X / 2.0f);
return return
RayTrace(Vehicle, StartCenter, EndCenter) || RayCast(Vehicle, StartCenter, EndCenter) ||
RayTrace(Vehicle, StartRight, EndRight) || RayCast(Vehicle, StartRight, EndRight) ||
RayTrace(Vehicle, StartLeft, EndLeft); RayCast(Vehicle, StartLeft, EndLeft);
} }
template <typename T> template <typename T>
@ -70,8 +79,8 @@ static void ClearQueue(std::queue<T> &Queue)
// -- Constructor and destructor ----------------------------------------------- // -- Constructor and destructor -----------------------------------------------
// ============================================================================= // =============================================================================
AWheeledVehicleAIController::AWheeledVehicleAIController(const FObjectInitializer& ObjectInitializer) : AWheeledVehicleAIController::AWheeledVehicleAIController(const FObjectInitializer &ObjectInitializer)
Super(ObjectInitializer) : Super(ObjectInitializer)
{ {
RandomEngine = CreateDefaultSubobject<URandomEngine>(TEXT("RandomEngine")); RandomEngine = CreateDefaultSubobject<URandomEngine>(TEXT("RandomEngine"));
@ -150,8 +159,8 @@ void AWheeledVehicleAIController::ConfigureAutopilot(const bool Enable)
ClearQueue(TargetLocations); ClearQueue(TargetLocations);
Vehicle->SetAIVehicleState( Vehicle->SetAIVehicleState(
bAutopilotEnabled ? bAutopilotEnabled ?
ECarlaWheeledVehicleState::FreeDriving : ECarlaWheeledVehicleState::FreeDriving :
ECarlaWheeledVehicleState::AutopilotOff); ECarlaWheeledVehicleState::AutopilotOff);
} }
// ============================================================================= // =============================================================================
@ -162,10 +171,12 @@ void AWheeledVehicleAIController::SetFixedRoute(
const TArray<FVector> &Locations, const TArray<FVector> &Locations,
const bool bOverwriteCurrent) const bool bOverwriteCurrent)
{ {
if (bOverwriteCurrent) { if (bOverwriteCurrent)
{
ClearQueue(TargetLocations); ClearQueue(TargetLocations);
} }
for (auto &Location : Locations) { for (auto &Location : Locations)
{
TargetLocations.emplace(Location); TargetLocations.emplace(Location);
} }
} }
@ -176,8 +187,9 @@ void AWheeledVehicleAIController::SetFixedRoute(
void AWheeledVehicleAIController::TickAutopilotController() void AWheeledVehicleAIController::TickAutopilotController()
{ {
#if WITH_EDITOR #if WITH_EDITOR // This happens in simulation mode in editor.
if (Vehicle == nullptr) { // This happens in simulation mode in editor. if (Vehicle == nullptr)
{
bAutopilotEnabled = false; bAutopilotEnabled = false;
return; return;
} }
@ -185,37 +197,45 @@ void AWheeledVehicleAIController::TickAutopilotController()
check(Vehicle != nullptr); check(Vehicle != nullptr);
if (RoadMap == nullptr) {
return;
}
FVector Direction; FVector Direction;
float Steering; float Steering;
if (!TargetLocations.empty()) { if (!TargetLocations.empty())
{
Steering = GoToNextTargetLocation(Direction); Steering = GoToNextTargetLocation(Direction);
} else { }
Steering = CalcStreeringValue(Direction); else
{
Steering = RoadMap != nullptr ? CalcStreeringValue(Direction) : 0.0f;
Direction = Vehicle->GetVehicleTransform().GetRotation().Rotator().Vector();
} }
// Speed in km/h. // Speed in km/h.
const auto Speed = Vehicle->GetVehicleForwardSpeed() * 0.036f; const auto Speed = Vehicle->GetVehicleForwardSpeed() * 0.036f;
float Throttle; float Throttle;
if (TrafficLightState != ETrafficLightState::Green) { if (TrafficLightState != ETrafficLightState::Green)
{
Vehicle->SetAIVehicleState(ECarlaWheeledVehicleState::WaitingForRedLight); Vehicle->SetAIVehicleState(ECarlaWheeledVehicleState::WaitingForRedLight);
Throttle = Stop(Speed); Throttle = Stop(Speed);
} else if (IsThereAnObstacleAhead(*Vehicle, Speed, Direction)) { }
else if (IsThereAnObstacleAhead(*Vehicle, Speed, Direction))
{
Vehicle->SetAIVehicleState(ECarlaWheeledVehicleState::ObstacleAhead); Vehicle->SetAIVehicleState(ECarlaWheeledVehicleState::ObstacleAhead);
Throttle = Stop(Speed); Throttle = Stop(Speed);
} else { }
else
{
Throttle = Move(Speed); Throttle = Move(Speed);
} }
if (Throttle < 0.001f) { if (Throttle < 0.001f)
{
AutopilotControl.Brake = 1.0f; AutopilotControl.Brake = 1.0f;
AutopilotControl.Throttle = 0.0f; AutopilotControl.Throttle = 0.0f;
} else { }
else
{
AutopilotControl.Brake = 0.0f; AutopilotControl.Brake = 0.0f;
AutopilotControl.Throttle = Throttle; AutopilotControl.Throttle = Throttle;
} }
@ -225,23 +245,27 @@ void AWheeledVehicleAIController::TickAutopilotController()
float AWheeledVehicleAIController::GoToNextTargetLocation(FVector &Direction) float AWheeledVehicleAIController::GoToNextTargetLocation(FVector &Direction)
{ {
// Get middle point between the two front wheels. // Get middle point between the two front wheels.
const auto CurrentLocation = [&](){ const auto CurrentLocation = [&]() {
const auto &Wheels = Vehicle->GetVehicleMovementComponent()->Wheels; const auto &Wheels = Vehicle->GetVehicleMovementComponent()->Wheels;
check((Wheels.Num() > 1) && (Wheels[0u] != nullptr) && (Wheels[1u] != nullptr)); check((Wheels.Num() > 1) && (Wheels[0u] != nullptr) && (Wheels[1u] != nullptr));
return (Wheels[0u]->Location + Wheels[1u]->Location) / 2.0f; return (Wheels[0u]->Location + Wheels[1u]->Location) / 2.0f;
}(); } ();
const auto Target = [&](){ const auto Target = [&]() {
const auto &Result = TargetLocations.front(); const auto &Result = TargetLocations.front();
return FVector{Result.X, Result.Y, CurrentLocation.Z}; return FVector{Result.X, Result.Y, CurrentLocation.Z};
}(); } ();
if (Target.Equals(CurrentLocation, 200.0f)) { if (Target.Equals(CurrentLocation, 200.0f))
{
TargetLocations.pop(); TargetLocations.pop();
if (!TargetLocations.empty()) { if (!TargetLocations.empty())
{
return GoToNextTargetLocation(Direction); return GoToNextTargetLocation(Direction);
} else { }
return CalcStreeringValue(Direction); else
{
return RoadMap != nullptr ? CalcStreeringValue(Direction) : 0.0f;
} }
} }
@ -257,16 +281,26 @@ float AWheeledVehicleAIController::GoToNextTargetLocation(FVector &Direction)
float angle = dirAngle - actorAngle; float angle = dirAngle - actorAngle;
if (angle > 180.0f) { angle -= 360.0f;} else if (angle < -180.0f) { if (angle > 180.0f)
{
angle -= 360.0f;
}
else if (angle < -180.0f)
{
angle += 360.0f; angle += 360.0f;
} }
float Steering = 0.0f; float Steering = 0.0f;
if (angle < -MaximumSteerAngle) { if (angle < -MaximumSteerAngle)
{
Steering = -1.0f; Steering = -1.0f;
} else if (angle > MaximumSteerAngle) { }
else if (angle > MaximumSteerAngle)
{
Steering = 1.0f; Steering = 1.0f;
} else { }
else
{
Steering += angle / MaximumSteerAngle; Steering += angle / MaximumSteerAngle;
} }
@ -285,9 +319,10 @@ float AWheeledVehicleAIController::CalcStreeringValue(FVector &direction)
float forwardMagnitude = BoxExtent.X / 2.0f; float forwardMagnitude = BoxExtent.X / 2.0f;
float Magnitude = (float) sqrt(pow((double) leftSensorPosition.X, 2.0) + pow((double) leftSensorPosition.Y, 2.0)); float Magnitude =
(float) sqrt(pow((double) leftSensorPosition.X, 2.0) + pow((double) leftSensorPosition.Y, 2.0));
//same for the right and left // same for the right and left
float offset = FGenericPlatformMath::Acos(forwardMagnitude / Magnitude); float offset = FGenericPlatformMath::Acos(forwardMagnitude / Magnitude);
float actorAngle = forward.UnitCartesianToSpherical().Y; float actorAngle = forward.UnitCartesianToSpherical().Y;
@ -304,19 +339,32 @@ float AWheeledVehicleAIController::CalcStreeringValue(FVector &direction)
leftSensorPosition.Y = sinL * Magnitude; leftSensorPosition.Y = sinL * Magnitude;
leftSensorPosition.X = cosL * Magnitude; leftSensorPosition.X = cosL * Magnitude;
FVector rightPositon = GetPawn()->GetActorLocation() + FVector(rightSensorPosition.X, rightSensorPosition.Y, 0.0f); FVector rightPositon = GetPawn()->GetActorLocation() + FVector(rightSensorPosition.X,
FVector leftPosition = GetPawn()->GetActorLocation() + FVector(leftSensorPosition.X, leftSensorPosition.Y, 0.0f); rightSensorPosition.Y,
0.0f);
FVector leftPosition = GetPawn()->GetActorLocation() + FVector(leftSensorPosition.X,
leftSensorPosition.Y,
0.0f);
FRoadMapPixelData rightRoadData = RoadMap->GetDataAt(rightPositon); FRoadMapPixelData rightRoadData = RoadMap->GetDataAt(rightPositon);
if (!rightRoadData.IsRoad()) { steering -= 0.2f;} if (!rightRoadData.IsRoad())
{
steering -= 0.2f;
}
FRoadMapPixelData leftRoadData = RoadMap->GetDataAt(leftPosition); FRoadMapPixelData leftRoadData = RoadMap->GetDataAt(leftPosition);
if (!leftRoadData.IsRoad()) { steering += 0.2f;} if (!leftRoadData.IsRoad())
{
steering += 0.2f;
}
FRoadMapPixelData roadData = RoadMap->GetDataAt(GetPawn()->GetActorLocation()); FRoadMapPixelData roadData = RoadMap->GetDataAt(GetPawn()->GetActorLocation());
if (!roadData.IsRoad()) { if (!roadData.IsRoad())
{
steering = 0.0f; steering = 0.0f;
} else if (roadData.HasDirection()) { }
else if (roadData.HasDirection())
{
direction = roadData.GetDirection(); direction = roadData.GetDirection();
FVector right = rightRoadData.GetDirection(); FVector right = rightRoadData.GetDirection();
@ -334,30 +382,61 @@ float AWheeledVehicleAIController::CalcStreeringValue(FVector &direction)
actorAngle *= (180.0 / PI); actorAngle *= (180.0 / PI);
float min = dirAngle - 90.0f; float min = dirAngle - 90.0f;
if (min < -180.0f) { min = 180.0f + (min + 180.0f);} if (min < -180.0f)
{
min = 180.0f + (min + 180.0f);
}
float max = dirAngle + 90.0f; float max = dirAngle + 90.0f;
if (max > 180.0f) { max = -180.0f + (max - 180.0f);} if (max > 180.0f)
{
max = -180.0f + (max - 180.0f);
}
if (dirAngle < -90.0 || dirAngle > 90.0) { if (dirAngle < -90.0 || dirAngle > 90.0)
if (rightAngle < min && rightAngle > max) { steering -= 0.2f;} {
if (leftAngle < min && leftAngle > max) { steering += 0.2f;} if (rightAngle < min && rightAngle > max)
} else { {
if (rightAngle < min || rightAngle > max) { steering -= 0.2f;} steering -= 0.2f;
if (leftAngle < min || leftAngle > max) { steering += 0.2f;} }
if (leftAngle < min && leftAngle > max)
{
steering += 0.2f;
}
}
else
{
if (rightAngle < min || rightAngle > max)
{
steering -= 0.2f;
}
if (leftAngle < min || leftAngle > max)
{
steering += 0.2f;
}
} }
float angle = dirAngle - actorAngle; float angle = dirAngle - actorAngle;
if (angle > 180.0f) { angle -= 360.0f;} else if (angle < -180.0f) { if (angle > 180.0f)
{
angle -= 360.0f;
}
else if (angle < -180.0f)
{
angle += 360.0f; angle += 360.0f;
} }
if (angle < -MaximumSteerAngle) { if (angle < -MaximumSteerAngle)
{
steering = -1.0f; steering = -1.0f;
} else if (angle > MaximumSteerAngle) { }
else if (angle > MaximumSteerAngle)
{
steering = 1.0f; steering = 1.0f;
} else { }
else
{
steering += angle / MaximumSteerAngle; steering += angle / MaximumSteerAngle;
} }
} }
@ -366,16 +445,23 @@ float AWheeledVehicleAIController::CalcStreeringValue(FVector &direction)
return steering; return steering;
} }
float AWheeledVehicleAIController::Stop(const float Speed) { float AWheeledVehicleAIController::Stop(const float Speed)
{
return (Speed >= 1.0f ? -Speed / SpeedLimit : 0.0f); return (Speed >= 1.0f ? -Speed / SpeedLimit : 0.0f);
} }
float AWheeledVehicleAIController::Move(const float Speed) { float AWheeledVehicleAIController::Move(const float Speed)
if (Speed >= SpeedLimit) { {
if (Speed >= SpeedLimit)
{
return Stop(Speed); return Stop(Speed);
} else if (Speed >= SpeedLimit - 10.0f) { }
else if (Speed >= SpeedLimit - 10.0f)
{
return 0.5f; return 0.5f;
} else { }
else
{
return 1.0f; return 1.0f;
} }
} }

View File

@ -29,9 +29,10 @@ class CARLA_API AWheeledVehicleAIController : public APlayerController
/// @name Constructor and destructor /// @name Constructor and destructor
// =========================================================================== // ===========================================================================
/// @{ /// @{
public: public:
AWheeledVehicleAIController(const FObjectInitializer& ObjectInitializer); AWheeledVehicleAIController(const FObjectInitializer &ObjectInitializer);
~AWheeledVehicleAIController(); ~AWheeledVehicleAIController();
@ -40,6 +41,7 @@ public:
/// @name APlayerController overrides /// @name APlayerController overrides
// =========================================================================== // ===========================================================================
/// @{ /// @{
public: public:
void Possess(APawn *aPawn) override; void Possess(APawn *aPawn) override;
@ -53,6 +55,7 @@ public:
/// @name Possessed vehicle /// @name Possessed vehicle
// =========================================================================== // ===========================================================================
/// @{ /// @{
public: public:
UFUNCTION(Category = "Wheeled Vehicle Controller", BlueprintCallable) UFUNCTION(Category = "Wheeled Vehicle Controller", BlueprintCallable)
@ -83,6 +86,7 @@ public:
/// @name Road map /// @name Road map
// =========================================================================== // ===========================================================================
/// @{ /// @{
public: public:
void SetRoadMap(URoadMap *InRoadMap) void SetRoadMap(URoadMap *InRoadMap)
@ -101,6 +105,7 @@ public:
/// @name Random engine /// @name Random engine
// =========================================================================== // ===========================================================================
/// @{ /// @{
public: public:
UFUNCTION(Category = "Random Engine", BlueprintCallable) UFUNCTION(Category = "Random Engine", BlueprintCallable)
@ -115,6 +120,7 @@ public:
/// @name Autopilot /// @name Autopilot
// =========================================================================== // ===========================================================================
/// @{ /// @{
public: public:
UFUNCTION(Category = "Wheeled Vehicle Controller", BlueprintCallable) UFUNCTION(Category = "Wheeled Vehicle Controller", BlueprintCallable)
@ -126,7 +132,8 @@ public:
UFUNCTION(Category = "Wheeled Vehicle Controller", BlueprintCallable) UFUNCTION(Category = "Wheeled Vehicle Controller", BlueprintCallable)
void SetAutopilot(bool Enable) void SetAutopilot(bool Enable)
{ {
if (IsAutopilotEnabled() != Enable) { if (IsAutopilotEnabled() != Enable)
{
ConfigureAutopilot(Enable); ConfigureAutopilot(Enable);
} }
} }
@ -146,6 +153,7 @@ private:
/// @name Traffic /// @name Traffic
// =========================================================================== // ===========================================================================
/// @{ /// @{
public: public:
/// Get current speed limit in km/h. /// Get current speed limit in km/h.
@ -176,9 +184,23 @@ public:
TrafficLightState = InTrafficLightState; TrafficLightState = InTrafficLightState;
} }
/// Get traffic light currently affecting this vehicle.
UFUNCTION(Category = "Wheeled Vehicle Controller", BlueprintCallable)
ATrafficLightBase *GetTrafficLight() const
{
return TrafficLight;
}
/// Set traffic light currently affecting this vehicle.
UFUNCTION(Category = "Wheeled Vehicle Controller", BlueprintCallable)
void SetTrafficLight(ATrafficLightBase *InTrafficLight)
{
TrafficLight = InTrafficLight;
}
/// Set a fixed route to follow if autopilot is enabled. /// Set a fixed route to follow if autopilot is enabled.
UFUNCTION(Category = "Wheeled Vehicle Controller", BlueprintCallable) UFUNCTION(Category = "Wheeled Vehicle Controller", BlueprintCallable)
void SetFixedRoute(const TArray<FVector> &Locations, bool bOverwriteCurrent=true); void SetFixedRoute(const TArray<FVector> &Locations, bool bOverwriteCurrent = true);
/// @} /// @}
// =========================================================================== // ===========================================================================
@ -212,6 +234,8 @@ private:
// =========================================================================== // ===========================================================================
// -- Member variables ------------------------------------------------------- // -- Member variables -------------------------------------------------------
// =========================================================================== // ===========================================================================
/// @{
private: private:
UPROPERTY() UPROPERTY()
@ -235,6 +259,9 @@ private:
UPROPERTY(VisibleAnywhere) UPROPERTY(VisibleAnywhere)
float MaximumSteerAngle = -1.0f; float MaximumSteerAngle = -1.0f;
UPROPERTY()
ATrafficLightBase *TrafficLight;
FVehicleControl AutopilotControl; FVehicleControl AutopilotControl;
std::queue<FVector> TargetLocations; std::queue<FVector> TargetLocations;

View File

@ -153,7 +153,8 @@ unset BOOST_BASENAME
# -- Get rpclib and compile it with libc++ and libstdc++ ----------------------- # -- Get rpclib and compile it with libc++ and libstdc++ -----------------------
# ============================================================================== # ==============================================================================
RPCLIB_BASENAME=rpclib-d1146b7-ex RPCLIB_PATCH=v2.2.1_c1
RPCLIB_BASENAME=rpclib-${RPCLIB_PATCH}
RPCLIB_LIBCXX_INCLUDE=${PWD}/${RPCLIB_BASENAME}-libcxx-install/include RPCLIB_LIBCXX_INCLUDE=${PWD}/${RPCLIB_BASENAME}-libcxx-install/include
RPCLIB_LIBCXX_LIBPATH=${PWD}/${RPCLIB_BASENAME}-libcxx-install/lib RPCLIB_LIBCXX_LIBPATH=${PWD}/${RPCLIB_BASENAME}-libcxx-install/lib
@ -170,10 +171,7 @@ else
log "Retrieving rpclib." log "Retrieving rpclib."
git clone https://github.com/rpclib/rpclib.git ${RPCLIB_BASENAME}-source git clone -b ${RPCLIB_PATCH} https://github.com/carla-simulator/rpclib.git ${RPCLIB_BASENAME}-source
pushd ${RPCLIB_BASENAME}-source >/dev/null
git reset --hard d1146b7
popd >/dev/null
log "Building rpclib with libc++." log "Building rpclib with libc++."