Update PythonAPI docu

+ Codeformatting of RSS parts
This commit is contained in:
Bernd Gassmann 2020-07-03 17:16:31 +02:00 committed by Marc Garcia Puig
parent 88ae9d04ae
commit 0332185e6f
9 changed files with 138 additions and 145 deletions

View File

@ -1499,9 +1499,9 @@ The ego route.
- <a name="carla.RssActorConstellationData.ego_dynamics_on_route"></a>**<font color="#f8805a">ego_dynamics_on_route</font>** (_[carla.RssEgoDynamicsOnRoute](#carla.RssEgoDynamicsOnRoute)_)
Current ego vehicle dynamics regarding the route.
- <a name="carla.RssActorConstellationData.other_match_object"></a>**<font color="#f8805a">other_match_object</font>** (_<a href="https://ad-map-access.readthedocs.io/en/latest/ad_map_access/apidoc/html/structad_1_1map_1_1match_1_1Object.html">libad_map_access_python.Object</a>_)
The other object's map matched information.
The other object's map matched information. This is only valid if 'other_actor' is not 'None'.
- <a name="carla.RssActorConstellationData.other_actor"></a>**<font color="#f8805a">other_actor</font>** (_[carla.Actor](#carla.Actor)_)
The other actor.
The other actor. This is 'None' in case of query of default parameters or articial objects of kind <a href="https://intel.github.io/ad-rss-lib/doxygen/ad_rss/namespacead_1_1rss_1_1world.html#a6432f1ef8d0657b4f21ed5966aca1625">libad_rss_python.ObjectType.ArtificialObject</a> with no dedicated '[carla.Actor](#carla.Actor)' (as e.g. for the [road boundaries](ref_sensors.md#rss-sensor) at the moment).
<h3>Methods</h3>
@ -1514,13 +1514,13 @@ The other actor.
Data structure that should be returned by the callback registered by RssSensor.register_actor_constellation_callback().
<h3>Instance Variables</h3>
- <a name="carla.RssActorConstellationResult.rss_calculation_mode"></a>**<font color="#f8805a">rss_calculation_mode</font>** (_<a href="https://TODO">libad_rss_map_integration_python.RssMode_TODO</a>_)
- <a name="carla.RssActorConstellationResult.rss_calculation_mode"></a>**<font color="#f8805a">rss_calculation_mode</font>** (_<a href="https://intel.github.io/ad-rss-lib/doxygen/ad_rss_map_integration/namespacead_1_1rss_1_1map.html#adcb01232986ed83a0c540cd5d03ef495">libad_rss_map_integration_python.RssMode</a>_)
The calculation mode to be applied with the actor.
- <a name="carla.RssActorConstellationResult.restrict_speed_limit_mode"></a>**<font color="#f8805a">restrict_speed_limit_mode</font>** (_<a href="https://TODO">libad_rss_map_integration_python.RestrictSpeedLimitMode_TODO</a>_)
- <a name="carla.RssActorConstellationResult.restrict_speed_limit_mode"></a>**<font color="#f8805a">restrict_speed_limit_mode</font>** (_<a href="https://intel.github.io/ad-rss-lib/doxygen/ad_rss_map_integration/classad_1_1rss_1_1map_1_1RssSceneCreation.html#a403aae6dce3c77a8aec01dd9808dd964">libad_rss_map_integration_python.RestrictSpeedLimitMode</a>_)
The mode for restricting speed limit.
- <a name="carla.RssActorConstellationResult.ego_vehicle_dynamics"></a>**<font color="#f8805a">ego_vehicle_dynamics</font>** (_<a href="https://intel.github.io/ad-rss-lib/doxygen/ad_rss/structad_1_1rss_1_1world_1_1RssDynamics.html">libad_rss_python.RssDynamics</a>_)
The RSS dynamics to be applied for the ego vehicle.
- <a name="carla.RssActorConstellationResult.actor_object_type"></a>**<font color="#f8805a">actor_object_type</font>** (_libad_rss_python.ObjectType_)
- <a name="carla.RssActorConstellationResult.actor_object_type"></a>**<font color="#f8805a">actor_object_type</font>** (_<a href="https://intel.github.io/ad-rss-lib/doxygen/ad_rss/namespacead_1_1rss_1_1world.html#a6432f1ef8d0657b4f21ed5966aca1625">libad_rss_python.ObjectType</a>_)
The RSS object type to be used for the actor.
- <a name="carla.RssActorConstellationResult.actor_dynamics"></a>**<font color="#f8805a">actor_dynamics</font>** (_<a href="https://intel.github.io/ad-rss-lib/doxygen/ad_rss/structad_1_1rss_1_1world_1_1RssDynamics.html">libad_rss_python.RssDynamics</a>_)
The RSS dynamics to be applied for the actor.
@ -1589,7 +1589,7 @@ Enum declaration used in [carla.RssSensor](#carla.RssSensor) to set the log leve
---
## carla.RssResponse<a name="carla.RssResponse"></a>
<div style="padding-left:30px;margin-top:-20px"><small><b>Inherited from _[carla.SensorData](#carla.SensorData)_</b></small></div></p><p>Class that contains the output of a [carla.RssSensor](#carla.RssSensor). This is the result of the RSS calculations performed for the parent vehicle of the sensor.
<div style="padding-left:30px;margin-top:-20px"><small><b>Inherited from _[carla.SensorData](#carla.SensorData)_</b></small></div></p><p>Class that contains the output of a [carla.RssSensor](#carla.RssSensor). This is the result of the RSS calculations performed for the parent vehicle of the sensor.
A [carla.RssRestrictor](#carla.RssRestrictor) will use the data to modify the [carla.VehicleControl](#carla.VehicleControl) of the vehicle.
@ -1598,8 +1598,6 @@ A [carla.RssRestrictor](#carla.RssRestrictor) will use the data to modify the [c
States if the response is valid. It is __False__ if calculations failed or an exception occured.
- <a name="carla.RssResponse.proper_response"></a>**<font color="#f8805a">proper_response</font>** (_<a href="https://intel.github.io/ad-rss-lib/doxygen/ad_rss/structad_1_1rss_1_1state_1_1ProperResponse.html">libad_rss_python.ProperResponse</a>_)
The proper response that the RSS calculated for the vehicle.
- <a name="carla.RssResponse.acceleration_restriction"></a>**<font color="#f8805a">acceleration_restriction</font>** (_<a href="https://intel.github.io/ad-rss-lib/doxygen/ad_rss/structad_1_1rss_1_1world_1_1AccelerationRestriction.html">libad_rss_python.AccelerationRestriction</a>_)
Acceleration restrictions to be applied, according to the RSS calculation.
- <a name="carla.RssResponse.rss_state_snapshot"></a>**<font color="#f8805a">rss_state_snapshot</font>** (_<a href="https://intel.github.io/ad-rss-lib/doxygen/ad_rss/structad_1_1rss_1_1state_1_1RssStateSnapshot.html">libad_rss_python.RssStateSnapshot</a>_)
Detailed RSS states at the current moment in time.
- <a name="carla.RssResponse.ego_dynamics_on_route"></a>**<font color="#f8805a">ego_dynamics_on_route</font>** (_[carla.RssEgoDynamicsOnRoute](#carla.RssEgoDynamicsOnRoute)_)
@ -1643,19 +1641,19 @@ Disables the _stay on road_ feature.
---
## carla.RssSensor<a name="carla.RssSensor"></a>
<div style="padding-left:30px;margin-top:-20px"><small><b>Inherited from _[carla.Sensor](#carla.Sensor)_</b></small></div></p><p>This sensor works a bit differently than the rest. Take look at the [specific documentation](adv_rss.md), and the [rss sensor reference](ref_sensors.md#rss-sensor) to gain full understanding of it.
<div style="padding-left:30px;margin-top:-20px"><small><b>Inherited from _[carla.Sensor](#carla.Sensor)_</b></small></div></p><p>This sensor works a bit differently than the rest. Take look at the [specific documentation](adv_rss.md), and the [rss sensor reference](ref_sensors.md#rss-sensor) to gain full understanding of it.
The RSS sensor uses world information, and a [RSS library](https://github.com/intel/ad-rss-lib) to make safety checks on a vehicle. The output retrieved by the sensor is a [carla.RssResponse](#carla.RssResponse). This will be used by a [carla.RssRestrictor](#carla.RssRestrictor) to modify a [carla.VehicleControl](#carla.VehicleControl) before applying it to a vehicle.
<h3>Instance Variables</h3>
- <a name="carla.RssSensor.ego_vehicle_dynamics"></a>**<font color="#f8805a">ego_vehicle_dynamics</font>** (_libad_rss_python.RssDynamics_)
States the [RSS parameters](https://intel.github.io/ad-rss-lib/ad_rss/Appendix-ParameterDiscussion/) that the sensor will consider for the ego vehicle.
States the [RSS parameters](https://intel.github.io/ad-rss-lib/ad_rss/Appendix-ParameterDiscussion/) that the sensor will consider for the ego vehicle if no actor constellation callback is registered.
- <a name="carla.RssSensor.other_vehicle_dynamics"></a>**<font color="#f8805a">other_vehicle_dynamics</font>** (_libad_rss_python.RssDynamics_)
States the [RSS parameters](https://intel.github.io/ad-rss-lib/ad_rss/Appendix-ParameterDiscussion/) that the sensor will consider for the rest of vehicles.
States the [RSS parameters](https://intel.github.io/ad-rss-lib/ad_rss/Appendix-ParameterDiscussion/) that the sensor will consider for the rest of vehicles if no actor constellation callback is registered.
- <a name="carla.RssSensor.pedestrian_dynamics"></a>**<font color="#f8805a">pedestrian_dynamics</font>** (_libad_rss_python.RssDynamics_)
States the [RSS parameters](https://intel.github.io/ad-rss-lib/ad_rss/Appendix-ParameterDiscussion/) that the sensor will consider for pedestrians if no actor constellation callback is registered.
- <a name="carla.RssSensor.road_boundaries_mode"></a>**<font color="#f8805a">road_boundaries_mode</font>** (_[carla.RssRoadBoundariesMode](#carla.RssRoadBoundariesMode)_)
Switches the [stay on road](https://intel.github.io/ad-rss-lib/ad_rss_map_integration/HandleRoadBoundaries/) feature. By default is __On__.
- <a name="carla.RssSensor.visualization_mode"></a>**<font color="#f8805a">visualization_mode</font>** (_[carla.RssVisualizationMode](#carla.RssVisualizationMode)_)
Sets the visualization of the RSS on the server side. By default is __All__. These drawings may delay de RSS so it is best to set this to __Off__ when evaluating RSS performance.
- <a name="carla.RssSensor.routing_targets"></a>**<font color="#f8805a">routing_targets</font>** (_vector<[carla.Transform](#carla.Transform)>_)
The current list of targets considered to route the vehicle. If no routing targets are defined, a route is generated at random.
@ -1669,7 +1667,7 @@ Erases the targets that have been appended to the route.
- <a name="carla.RssSensor.drop_route"></a>**<font color="#7fb800">drop_route</font>**(<font color="#00a6ed">**self**</font>)
Discards the current route. If there are targets remaining in **<font color="#f8805a">routing_targets</font>**, creates a new route using those. Otherwise, a new route is created at random.
- <a name="carla.RssSensor.register_actor_constellation_callback"></a>**<font color="#7fb800">register_actor_constellation_callback</font>**(<font color="#00a6ed">**self**</font>, <font color="#00a6ed">**callback**</font>)
Register a callback to customize a [carla.RssActorConstellationResult](#carla.RssActorConstellationResult).
Register a callback to customize a [carla.RssActorConstellationResult](#carla.RssActorConstellationResult). By this callback the settings of RSS parameters are done per actor constellation and the settings (ego_vehicle_dynamics, other_vehicle_dynamics and pedestrian_dynamics) have no effect.
- **Parameters:**
- `callback` The function to be called whenever a RSS situation is about to be calculated.
@ -1684,34 +1682,22 @@ Sets the log level.
---
## carla.RssVisualizationMode<a name="carla.RssVisualizationMode"></a>
Enum declaration used to state the visualization RSS calculations server side. Depending on these, the [carla.RssSensor](#carla.RssSensor) will use a [carla.DebugHelper](#carla.DebugHelper) to draw different elements. These drawings take some time and might delay the RSS responses. It is best to disable them when evaluating RSS performance.
<h3>Instance Variables</h3>
- <a name="carla.RssVisualizationMode.Off"></a>**<font color="#f8805a">Off</font>**
- <a name="carla.RssVisualizationMode.RouteOnly"></a>**<font color="#f8805a">RouteOnly</font>**
- <a name="carla.RssVisualizationMode.VehicleStateOnly"></a>**<font color="#f8805a">VehicleStateOnly</font>**
- <a name="carla.RssVisualizationMode.VehicleStateAndRoute"></a>**<font color="#f8805a">VehicleStateAndRoute</font>**
- <a name="carla.RssVisualizationMode.All"></a>**<font color="#f8805a">All</font>**
---
## carla.Sensor<a name="carla.Sensor"></a>
<div style="padding-left:30px;margin-top:-20px"><small><b>Inherited from _[carla.Actor](#carla.Actor)_</b></small></div></p><p>Sensors compound a specific family of actors quite diverse and unique. They are normally spawned as attachment/sons of a vehicle (take a look at [carla.World](#carla.World) to learn about actor spawning). Sensors are thoroughly designed to retrieve different types of data that they are listening to. The data they receive is shaped as different subclasses inherited from [carla.SensorData](#carla.SensorData) (depending on the sensor).
Most sensors can be divided in two groups: those receiving data on every tick (cameras, point clouds and some specific sensors) and those who only receive under certain circumstances (trigger detectors). CARLA provides a specific set of sensors and their blueprint can be found in [carla.BlueprintLibrary](#carla.BlueprintLibrary). All the information on their preferences and settlement can be found [here](ref_sensors.md), but the list of those available in CARLA so far goes as follow.
<b>Receive data on every tick.</b>
- [Depth camera](ref_sensors.md#depth-camera).
- [Gnss sensor](ref_sensors.md#gnss-sensor).
- [IMU sensor](ref_sensors.md#imu-sensor).
- [Lidar raycast](ref_sensors.md#lidar-raycast-sensor).
- [Radar](ref_sensors.md#radar-sensor).
- [RGB camera](ref_sensors.md#rgb-camera).
- [RSS sensor](ref_sensors.md#rss-sensor).
- [Semantic Segmentation camera](ref_sensors.md#semantic-segmentation-camera).
<b>Only receive data when triggered.</b>
- [Collision detector](ref_sensors.md#collision-detector).
- [Lane invasion detector](ref_sensors.md#lane-invasion-detector).
Most sensors can be divided in two groups: those receiving data on every tick (cameras, point clouds and some specific sensors) and those who only receive under certain circumstances (trigger detectors). CARLA provides a specific set of sensors and their blueprint can be found in [carla.BlueprintLibrary](#carla.BlueprintLibrary). All the information on their preferences and settlement can be found [here](ref_sensors.md), but the list of those available in CARLA so far goes as follow.
<b>Receive data on every tick.</b>
- [Depth camera](ref_sensors.md#depth-camera).
- [Gnss sensor](ref_sensors.md#gnss-sensor).
- [IMU sensor](ref_sensors.md#imu-sensor).
- [Lidar raycast](ref_sensors.md#lidar-raycast-sensor).
- [Radar](ref_sensors.md#radar-sensor).
- [RGB camera](ref_sensors.md#rgb-camera).
- [RSS sensor](ref_sensors.md#rss-sensor).
- [Semantic Segmentation camera](ref_sensors.md#semantic-segmentation-camera).
<b>Only receive data when triggered.</b>
- [Collision detector](ref_sensors.md#collision-detector).
- [Lane invasion detector](ref_sensors.md#lane-invasion-detector).
- [Obstacle detector](ref_sensors.md#obstacle-detector).
<h3>Instance Variables</h3>
@ -1732,15 +1718,15 @@ Commands the sensor to stop listening for data.
---
## carla.SensorData<a name="carla.SensorData"></a>
Base class for all the objects containing data generated by a [carla.Sensor](#carla.Sensor). This objects should be the argument of the function said sensor is listening to, in order to work with them. Each of these sensors needs for a specific type of sensor data. Hereunder is a list of the sensors and their corresponding data.
- Cameras (RGB, depth and semantic segmentation): [carla.Image](#carla.Image).
- Collision detector: [carla.CollisionEvent](#carla.CollisionEvent).
- Gnss detector: [carla.GnssMeasurement](#carla.GnssMeasurement).
- IMU detector: [carla.IMUMeasurement](#carla.IMUMeasurement).
- Lane invasion detector: [carla.LaneInvasionEvent](#carla.LaneInvasionEvent).
- Lidar raycast: [carla.LidarMeasurement](#carla.LidarMeasurement).
- Obstacle detector: [carla.ObstacleDetectionEvent](#carla.ObstacleDetectionEvent).
- Radar detector: [carla.RadarMeasurement](#carla.RadarMeasurement).
Base class for all the objects containing data generated by a [carla.Sensor](#carla.Sensor). This objects should be the argument of the function said sensor is listening to, in order to work with them. Each of these sensors needs for a specific type of sensor data. Hereunder is a list of the sensors and their corresponding data.
- Cameras (RGB, depth and semantic segmentation): [carla.Image](#carla.Image).
- Collision detector: [carla.CollisionEvent](#carla.CollisionEvent).
- Gnss detector: [carla.GnssMeasurement](#carla.GnssMeasurement).
- IMU detector: [carla.IMUMeasurement](#carla.IMUMeasurement).
- Lane invasion detector: [carla.LaneInvasionEvent](#carla.LaneInvasionEvent).
- Lidar raycast: [carla.LidarMeasurement](#carla.LidarMeasurement).
- Obstacle detector: [carla.ObstacleDetectionEvent](#carla.ObstacleDetectionEvent).
- Radar detector: [carla.RadarMeasurement](#carla.RadarMeasurement).
- RSS sensor: [carla.RssResponse](#carla.RssResponse).
<h3>Instance Variables</h3>

View File

@ -20,9 +20,9 @@
#include <ad/map/route/Planning.hpp>
#include <ad/rss/map/Logging.hpp>
#include <ad/rss/map/RssObjectConversion.hpp>
#include <ad/rss/map/RssObjectData.hpp>
#include <ad/rss/map/RssSceneCreator.hpp>
#include <ad/rss/state/RssStateOperation.hpp>
#include <ad/rss/map/RssObjectData.hpp>
#include <chrono>
#include <tuple>
@ -125,8 +125,7 @@ std::shared_ptr<spdlog::logger> getTimingLogger() {
}
RssCheck::RssCheck(float maximum_steering_angle)
: _maximum_steering_angle(maximum_steering_angle)
, _road_boundaries_mode(GetDefaultRoadBoundariesMode()) {
: _maximum_steering_angle(maximum_steering_angle), _road_boundaries_mode(GetDefaultRoadBoundariesMode()) {
_logger = getLogger();
_timing_logger = getTimingLogger();
_timing_logger->set_level(spdlog::level::off);
@ -146,7 +145,8 @@ RssCheck::RssCheck(float maximum_steering_angle)
::carla::rss::ActorConstellationResult actor_constellation_result;
actor_constellation_result.rss_calculation_mode = ::ad::rss::map::RssMode::NotRelevant;
actor_constellation_result.restrict_speed_limit_mode = ::ad::rss::map::RssSceneCreation::RestrictSpeedLimitMode::IncreasedSpeedLimit10;
actor_constellation_result.restrict_speed_limit_mode =
::ad::rss::map::RssSceneCreation::RestrictSpeedLimitMode::IncreasedSpeedLimit10;
actor_constellation_result.actor_object_type = ad::rss::world::ObjectType::Invalid;
actor_constellation_result.ego_vehicle_dynamics = this->_default_actor_constellation_callback_ego_vehicle_dynamics;
actor_constellation_result.actor_dynamics = this->_default_actor_constellation_callback_other_vehicle_dynamics;
@ -379,8 +379,8 @@ bool RssCheck::CheckObjects(carla::client::Timestamp const &timestamp,
#if DEBUG_TIMING
t_end = std::chrono::high_resolution_clock::now();
std::cout << "-> AN " << std::chrono::duration<double, std::milli>(t_end - t_start).count() << " end analyze results"
<< std::endl;
std::cout << "-> AN " << std::chrono::duration<double, std::milli>(t_end - t_start).count()
<< " end analyze results" << std::endl;
#endif
_carla_rss_state.ego_dynamics_on_route.time_since_epoch_check_end_ms =
@ -452,8 +452,7 @@ bool RssCheck::CheckObjects(carla::client::Timestamp const &timestamp,
actor_transform.rotation.InverseRotateVector(velocity);
::ad::physics::Speed speed(std::sqrt(velocity.x * velocity.x + velocity.y * velocity.y));
if ( velocity.x < 0. )
{
if (velocity.x < 0.) {
speed = -speed;
}
@ -693,7 +692,7 @@ EgoDynamicsOnRoute RssCheck::CalculateEgoDynamicsOnRoute(
new_dynamics.crossing_border = false;
// calculate the ego stopping distance, to be able to reduce the effort
::ad::rss::map::RssObjectData ego_object_data;
ego_object_data.id = ::ad::rss::world::ObjectId(0u);
ego_object_data.type = ::ad::rss::world::ObjectType::EgoVehicle;
@ -833,12 +832,11 @@ void RssCheck::RssObjectChecker::operator()(
auto other_heading_change = _rss_check.GetHeadingChange(*other_traffic_participant);
auto other_steering_angle = ::ad::physics::Angle(0.);
::ad::rss::map::RssObjectData ego_object_data;
ego_object_data.id = _carla_ego_vehicle.GetId();
ego_object_data.type = ::ad::rss::world::ObjectType::EgoVehicle;
ego_object_data.matchObject = _carla_rss_state.ego_match_object;
ego_object_data.speed = _carla_rss_state.ego_dynamics_on_route.ego_speed;
ego_object_data.speed = _carla_rss_state.ego_dynamics_on_route.ego_speed;
ego_object_data.yawRate = _carla_rss_state.ego_dynamics_on_route.ego_heading_change;
ego_object_data.steeringAngle = _carla_rss_state.ego_dynamics_on_route.ego_steering_angle;
ego_object_data.rssDynamics = actor_constellation_result.ego_vehicle_dynamics;
@ -851,14 +849,10 @@ void RssCheck::RssObjectChecker::operator()(
other_object_data.yawRate = other_heading_change;
other_object_data.steeringAngle = other_steering_angle;
other_object_data.rssDynamics = actor_constellation_result.actor_dynamics;
_scene_creation.appendScenes(
ego_object_data,
_carla_rss_state.ego_route,
other_object_data,
actor_constellation_result.restrict_speed_limit_mode,
_green_traffic_lights,
actor_constellation_result.rss_calculation_mode);
_scene_creation.appendScenes(ego_object_data, _carla_rss_state.ego_route, other_object_data,
actor_constellation_result.restrict_speed_limit_mode, _green_traffic_lights,
actor_constellation_result.rss_calculation_mode);
} catch (...) {
_rss_check._logger->error("Exception processing other traffic participant {} -> Ignoring it",
@ -912,19 +906,19 @@ void RssCheck::CreateWorldModel(carla::client::Timestamp const &timestamp, carla
// use 'smart' dynamics
auto ego_vehicle_dynamics = carla_rss_state.default_ego_vehicle_dynamics;
ego_vehicle_dynamics.alphaLat.accelMax = ::ad::physics::Acceleration(0.);
::ad::rss::map::RssObjectData ego_object_data;
ego_object_data.id = carla_ego_vehicle.GetId();
ego_object_data.type = ::ad::rss::world::ObjectType::EgoVehicle;
ego_object_data.matchObject = _carla_rss_state.ego_match_object;
ego_object_data.speed = _carla_rss_state.ego_dynamics_on_route.ego_speed;
ego_object_data.speed = _carla_rss_state.ego_dynamics_on_route.ego_speed;
ego_object_data.yawRate = _carla_rss_state.ego_dynamics_on_route.ego_heading_change;
ego_object_data.steeringAngle = _carla_rss_state.ego_dynamics_on_route.ego_steering_angle;
ego_object_data.rssDynamics = ego_vehicle_dynamics;
scene_creation.appendRoadBoundaries(ego_object_data, carla_rss_state.ego_route,
// since the route always expanded, route isn't required to expand any
// more
::ad::rss::map::RssSceneCreation::AppendRoadBoundariesMode::RouteOnly);
// since the route always expanded, route isn't required to expand any
// more
::ad::rss::map::RssSceneCreation::AppendRoadBoundariesMode::RouteOnly);
}
carla_rss_state.world_model = scene_creation.getWorldModel();
@ -1018,6 +1012,5 @@ void RssCheck::AnalyseCheckResults(CarlaRssState &carla_rss_state) const {
_logger->debug("RouteResponse: {}", carla_rss_state.proper_response);
}
} // namespace rss
} // namespace carla

View File

@ -98,7 +98,8 @@ struct ActorConstellationResult {
::ad::rss::map::RssMode rss_calculation_mode{::ad::rss::map::RssMode::NotRelevant};
/// The mode for restricting speed limit
::ad::rss::map::RssSceneCreation::RestrictSpeedLimitMode restrict_speed_limit_mode{::ad::rss::map::RssSceneCreation::RestrictSpeedLimitMode::None};
::ad::rss::map::RssSceneCreation::RestrictSpeedLimitMode restrict_speed_limit_mode{
::ad::rss::map::RssSceneCreation::RestrictSpeedLimitMode::None};
/// The Rss dynamics to be applied for the ego vehicle
::ad::rss::world::RssDynamics ego_vehicle_dynamics;
@ -137,8 +138,7 @@ public:
RssCheck(float max_steering_angle);
/// @brief constructor with actor constellation callback
RssCheck(float max_steering_angle,
ActorConstellationCallbackFunctionType rss_actor_constellation_callback,
RssCheck(float max_steering_angle, ActorConstellationCallbackFunctionType rss_actor_constellation_callback,
carla::SharedPtr<carla::client::Actor> const &carla_ego_actor);
/// @brief destructor
@ -215,7 +215,7 @@ private:
std::shared_ptr<spdlog::logger> _logger;
/// @brief logger for timing log messages
std::shared_ptr<spdlog::logger> _timing_logger;
/// @brief maximum steering angle
float _maximum_steering_angle;

View File

@ -14,10 +14,10 @@
#include "carla/Logging.h"
#include "carla/client/Map.h"
#include "carla/client/Sensor.h"
#include "carla/client/Vehicle.h"
#include "carla/client/detail/Simulator.h"
#include "carla/rss/RssCheck.h"
#include "carla/sensor/data/RssResponse.h"
#include "carla/client/Vehicle.h"
namespace carla {
namespace client {
@ -56,7 +56,7 @@ void RssSensor::Listen(CallbackFunctionType callback) {
throw_exception(std::runtime_error(GetDisplayId() + ": parent is not a vehicle"));
return;
}
// get maximum steering angle
float max_steer_angle_deg = 0.f;
for (auto const &wheel : vehicle->GetPhysicsControl().GetWheels()) {
@ -78,7 +78,8 @@ void RssSensor::Listen(CallbackFunctionType callback) {
if (_rss_actor_constellation_callback == nullptr) {
_rss_check = std::make_shared<::carla::rss::RssCheck>(max_steering_angle);
} else {
_rss_check = std::make_shared<::carla::rss::RssCheck>(max_steering_angle, _rss_actor_constellation_callback, GetParent());
_rss_check =
std::make_shared<::carla::rss::RssCheck>(max_steering_angle, _rss_actor_constellation_callback, GetParent());
}
auto self = boost::static_pointer_cast<RssSensor>(shared_from_this());

View File

@ -42,15 +42,10 @@ namespace sensor {
namespace data {
std::ostream &operator<<(std::ostream &out, const RssResponse &resp) {
out << "RssResponse(frame=" << resp.GetFrame()
<< ", timestamp=" << resp.GetTimestamp()
<< ", valid=" << resp.GetResponseValid()
<< ", proper_response=" << resp.GetProperResponse()
<< ", rss_state_snapshot=" << resp.GetRssStateSnapshot()
<< ", situation_snapshot=" << resp.GetSituationSnapshot()
<< ", world_model=" << resp.GetWorldModel()
<< ", ego_dynamics_on_route=" << resp.GetEgoDynamicsOnRoute()
<< ')';
out << "RssResponse(frame=" << resp.GetFrame() << ", timestamp=" << resp.GetTimestamp()
<< ", valid=" << resp.GetResponseValid() << ", proper_response=" << resp.GetProperResponse()
<< ", rss_state_snapshot=" << resp.GetRssStateSnapshot() << ", situation_snapshot=" << resp.GetSituationSnapshot()
<< ", world_model=" << resp.GetWorldModel() << ", ego_dynamics_on_route=" << resp.GetEgoDynamicsOnRoute() << ')';
return out;
}

View File

@ -5,16 +5,16 @@
- class_name: SensorData
# - DESCRIPTION ------------------------
doc: >
Base class for all the objects containing data generated by a carla.Sensor. This objects should be the argument of the function said sensor is listening to, in order to work with them. Each of these sensors needs for a specific type of sensor data. Hereunder is a list of the sensors and their corresponding data.
- Cameras (RGB, depth and semantic segmentation): carla.Image.
- Collision detector: carla.CollisionEvent.
- Gnss detector: carla.GnssMeasurement.
- IMU detector: carla.IMUMeasurement.
- Lane invasion detector: carla.LaneInvasionEvent.
- Lidar raycast: carla.LidarMeasurement.
- Obstacle detector: carla.ObstacleDetectionEvent.
- Radar detector: carla.RadarMeasurement.
- RSS sensor: carla.RssResponse.
Base class for all the objects containing data generated by a carla.Sensor. This objects should be the argument of the function said sensor is listening to, in order to work with them. Each of these sensors needs for a specific type of sensor data. Hereunder is a list of the sensors and their corresponding data.
- Cameras (RGB, depth and semantic segmentation): carla.Image.
- Collision detector: carla.CollisionEvent.
- Gnss detector: carla.GnssMeasurement.
- IMU detector: carla.IMUMeasurement.
- Lane invasion detector: carla.LaneInvasionEvent.
- Lidar raycast: carla.LidarMeasurement.
- Obstacle detector: carla.ObstacleDetectionEvent.
- Radar detector: carla.RadarMeasurement.
- RSS sensor: carla.RssResponse.
# - PROPERTIES -------------------------
instance_variables:
- var_name: frame
@ -369,27 +369,22 @@
parent: carla.SensorData
# - DESCRIPTION ------------------------
doc: >
Class that contains the output of a carla.RssSensor. This is the result of the RSS calculations performed for the parent vehicle of the sensor.
Class that contains the output of a carla.RssSensor. This is the result of the RSS calculations performed for the parent vehicle of the sensor.
A carla.RssRestrictor will use the data to modify the carla.VehicleControl of the vehicle.
A carla.RssRestrictor will use the data to modify the carla.VehicleControl of the vehicle.
# - PROPERTIES -------------------------
instance_variables:
- var_name: response_valid
type: bool
doc: >
States if the response is valid. It is __False__ if calculations failed or an exception occured.
States if the response is valid. It is __False__ if calculations failed or an exception occured.
# --------------------------------------
- var_name: proper_response
type: <a href="https://intel.github.io/ad-rss-lib/doxygen/ad_rss/structad_1_1rss_1_1state_1_1ProperResponse.html">libad_rss_python.ProperResponse</a>
doc: >
The proper response that the RSS calculated for the vehicle.
# --------------------------------------
- var_name: acceleration_restriction
type: <a href="https://intel.github.io/ad-rss-lib/doxygen/ad_rss/structad_1_1rss_1_1world_1_1AccelerationRestriction.html">libad_rss_python.AccelerationRestriction</a>
doc: >
Acceleration restrictions to be applied, according to the RSS calculation.
# --------------------------------------
- var_name: rss_state_snapshot
type: <a href="https://intel.github.io/ad-rss-lib/doxygen/ad_rss/structad_1_1rss_1_1state_1_1RssStateSnapshot.html">libad_rss_python.RssStateSnapshot</a>
doc: >
@ -417,7 +412,7 @@
- class_name: RssEgoDynamicsOnRoute
# - DESCRIPTION ------------------------
doc: >
Part of the data contained inside a carla.RssResponse describing the state of the vehicle. The parameters include its current dynamics, and how it is heading regarding the target route.
Part of the data contained inside a carla.RssResponse describing the state of the vehicle. The parameters include its current dynamics, and how it is heading regarding the target route.
# - PROPERTIES -------------------------
instance_variables:
- var_name: ego_speed
@ -523,12 +518,13 @@
- var_name: other_match_object
type: <a href="https://ad-map-access.readthedocs.io/en/latest/ad_map_access/apidoc/html/structad_1_1map_1_1match_1_1Object.html">libad_map_access_python.Object</a>
doc: >
The other object's map matched information.
The other object's map matched information. This is only valid if 'other_actor' is not 'None'.
# --------------------------------------
- var_name: other_actor
type: carla.Actor
doc: >
The other actor.
The other actor. This is 'None' in case of query of default parameters or articial objects of kind <a href="https://intel.github.io/ad-rss-lib/doxygen/ad_rss/namespacead_1_1rss_1_1world.html#a6432f1ef8d0657b4f21ed5966aca1625">libad_rss_python.ObjectType.ArtificialObject</a>
with no dedicated 'carla.Actor' (as e.g. for the [road boundaries](ref_sensors.md#rss-sensor) at the moment)
# - METHODS ----------------------------
methods:
- def_name: __str__
@ -541,12 +537,12 @@
# - PROPERTIES -------------------------
instance_variables:
- var_name: rss_calculation_mode
type: <a href="https://TODO">libad_rss_map_integration_python.RssMode_TODO</a>
type: <a href="https://intel.github.io/ad-rss-lib/doxygen/ad_rss_map_integration/namespacead_1_1rss_1_1map.html#adcb01232986ed83a0c540cd5d03ef495">libad_rss_map_integration_python.RssMode</a>
doc: >
The calculation mode to be applied with the actor.
The calculation mode to be applied with the actor.
# --------------------------------------
- var_name: restrict_speed_limit_mode
type: <a href="https://TODO">libad_rss_map_integration_python.RestrictSpeedLimitMode_TODO</a>
type: <a href="https://intel.github.io/ad-rss-lib/doxygen/ad_rss_map_integration/classad_1_1rss_1_1map_1_1RssSceneCreation.html#a403aae6dce3c77a8aec01dd9808dd964">libad_rss_map_integration_python.RestrictSpeedLimitMode</a>
doc: >
The mode for restricting speed limit.
# --------------------------------------
@ -556,7 +552,7 @@
The RSS dynamics to be applied for the ego vehicle.
# --------------------------------------
- var_name: actor_object_type
type: libad_rss_python.ObjectType
type: <a href="https://intel.github.io/ad-rss-lib/doxygen/ad_rss/namespacead_1_1rss_1_1world.html#a6432f1ef8d0657b4f21ed5966aca1625">libad_rss_python.ObjectType</a>
doc: >
The RSS object type to be used for the actor.
# --------------------------------------
@ -572,7 +568,7 @@
- class_name: DVSEvent
# - DESCRIPTION ------------------------
doc: >
Class that defines a DVS event. An event is a quadruple, so a tuple of 4 elements, with `x`, `y` pixel coordinate location, timestamp `t` and polarity `pol` of the event. Learn more about them [here](ref_sensors.md).
Class that defines a DVS event. An event is a quadruple, so a tuple of 4 elements, with `x`, `y` pixel coordinate location, timestamp `t` and polarity `pol` of the event. Learn more about them [here](ref_sensors.md).
# - PROPERTIES -------------------------
instance_variables:
- var_name: x
@ -588,7 +584,7 @@
- var_name: t
type: int
doc: >
Timestamp of the moment the event happened.
Timestamp of the moment the event happened.
# --------------------------------------
- var_name: pol
type: bool
@ -602,23 +598,23 @@
- class_name: DVSEventArray
# - DESCRIPTION ------------------------
doc: >
Class that defines a stream of events in [carla.DVSEvent](#carla.DVSEvent). Such stream is an array of arbitrary size depending on the number of events. This class also stores the field of view, the height and width of the image and the timestamp from convenience. Learn more about them [here](ref_sensors.md).
Class that defines a stream of events in [carla.DVSEvent](#carla.DVSEvent). Such stream is an array of arbitrary size depending on the number of events. This class also stores the field of view, the height and width of the image and the timestamp from convenience. Learn more about them [here](ref_sensors.md).
# - PROPERTIES -------------------------
instance_variables:
- var_name: fov
type: float
doc: >
Horizontal field of view of the image in degrees.
Horizontal field of view of the image in degrees.
# --------------------------------------
- var_name: height
type: int
doc: >
Image height in pixels.
Image height in pixels.
# --------------------------------------
- var_name: width
type: int
doc: >
Image width in pixels.
Image width in pixels.
# --------------------------------------
- var_name: raw_data
type: bytes

View File

@ -279,6 +279,7 @@ class World(object):
# ==============================================================================
class Camera(object):
def __init__(self, parent_actor, display_dimensions):
self.surface = None
self._parent = parent_actor
@ -351,7 +352,8 @@ class VehicleControl(object):
[
(0, 0),
(0, self.MOUSE_STEERING_RANGE * 2 - line_width),
(self.MOUSE_STEERING_RANGE * 2 - line_width, self.MOUSE_STEERING_RANGE * 2 - line_width),
(self.MOUSE_STEERING_RANGE * 2 - line_width,
self.MOUSE_STEERING_RANGE * 2 - line_width),
(self.MOUSE_STEERING_RANGE * 2 - line_width, 0),
(0, 0)
], line_width)
@ -556,7 +558,7 @@ class VehicleControl(object):
max_val = self.MOUSE_STEERING_RANGE
lateral = -max_val if lateral < -max_val else max_val if lateral > max_val else lateral
longitudinal = -max_val if longitudinal < -max_val else max_val if longitudinal > max_val else longitudinal
self._control.steer = lateral/max_val
self._control.steer = lateral / max_val
if longitudinal < 0.0:
self._control.throttle = -longitudinal / max_val
self._control.brake = 0.0
@ -718,6 +720,7 @@ class HUD(object):
class FadingText(object):
def __init__(self, font, dim, pos):
self.font = font
self.dim = dim
@ -747,6 +750,7 @@ class FadingText(object):
class HelpText(object):
"""Helper class to handle text output using pygame"""
def __init__(self, font, width, height):

View File

@ -27,6 +27,7 @@ else:
class RssStateInfo(object):
def __init__(self, rss_state, ego_dynamics_on_route, actor_calculation_mode_map):
self.rss_state = rss_state
self.distance = -1
@ -54,6 +55,7 @@ class RssStateInfo(object):
class RssSensor(object):
def __init__(self, parent_actor, world, unstructured_scene_drawer, bounding_box_drawer, routing_targets=None):
self.sensor = None
self.unstructured_scene_drawer = unstructured_scene_drawer
@ -114,7 +116,7 @@ class RssSensor(object):
self.sensor.append_routing_target(target)
def _on_actor_constellation_request(self, actor_constellation_data):
#print("_on_actor_constellation_request: ", str(actor_constellation_data))
# print("_on_actor_constellation_request: ", str(actor_constellation_data))
actor_constellation_result = carla.RssActorConstellationResult()
actor_constellation_result.rss_calculation_mode = rssmap.RssMode.NotRelevant
@ -211,21 +213,26 @@ class RssSensor(object):
if other_outside_routeable_road:
# if the other is somewhat outside the standard routeable road (e.g. parked at the side, ...)
# we immediately decide for unstructured
# print("vehicle-{} unstructured: reason other outside routeable road".format(actor_id))
# print("vehicle-{} unstructured: reason other outside routeable
# road".format(actor_id))
actor_constellation_result.rss_calculation_mode = rssmap.RssMode.Unstructured
else:
# otherwise we have to look in the orientation delta in addition to get some basic idea of the
# constellation (we don't want to go into unstructured if we both waiting behind a red light...)
# constellation (we don't want to go into unstructured if we both waiting
# behind a red light...)
heading_delta = abs(float(actor_constellation_data.ego_match_object.enuPosition.heading -
actor_constellation_data.other_match_object.enuPosition.heading))
if heading_delta > 0.2: # around 11 degree
# print("vehicle-{} unstructured: reason heading delta {}".format(actor_id, heading_delta))
# print("vehicle-{} unstructured: reason heading delta
# {}".format(actor_id, heading_delta))
actor_constellation_result.rss_calculation_mode = rssmap.RssMode.Unstructured
self.change_to_unstructured_position_map[actor_id] = actor_constellation_data.other_match_object.enuPosition
self.change_to_unstructured_position_map[
actor_id] = actor_constellation_data.other_match_object.enuPosition
else:
# ego moves
if actor_distance < 10:
# if the ego moves, the other actor doesn't move an the mode was previously set to unstructured, keep it
# if the ego moves, the other actor doesn't move an the mode was
# previously set to unstructured, keep it
try:
if self.change_to_unstructured_position_map[actor_id] == actor_constellation_data.other_match_object.enuPosition:
heading_delta = abs(float(actor_constellation_data.ego_match_object.enuPosition.heading -
@ -247,7 +254,8 @@ class RssSensor(object):
# otherwise if standing at the intersection the acceleration within reaction time
# will allow to enter the intersection which current RSS implementation will immediately consider
# as dangerous
# print("_on_actor_constellation_result({}) setting accelMax to zero".format(actor_constellation_data.other_actor.id))
# print("_on_actor_constellation_result({}) setting accelMax to
# zero".format(actor_constellation_data.other_actor.id))
actor_constellation_result.actor_dynamics.alphaLon.accelMax = 0.
# store values for visualization
self.actor_calculation_mode_map[actor_id] = (
@ -268,7 +276,8 @@ class RssSensor(object):
# actor_constellation_result.ego_vehicle_dynamics.alphaLat.accelMax))
actor_constellation_result.ego_vehicle_dynamics.alphaLat.accelMax = min(20., abs_avg_route_accel_lat)
# print("_on_actor_constellation_result({}-{}): ".format(actor_id, actor_type_id), str(actor_constellation_result))
# print("_on_actor_constellation_result({}-{}): ".format(actor_id,
# actor_type_id), str(actor_constellation_result))
return actor_constellation_result
def destroy(self):

View File

@ -55,26 +55,34 @@ def render_rss_states(display, v_offset, font, individual_rss_states):
color = (0, 255, 0)
else:
color = (255, 0, 0)
pygame.draw.circle(display, color, (12, v_offset+7), 5)
pygame.draw.circle(display, color, (12, v_offset + 7), 5)
xpos = 184
if state.actor_calculation_mode == rssmap.RssMode.Structured:
if not state.rss_state.longitudinalState.isSafe and ((state.rss_state.longitudinalState.rssStateInformation.evaluator == "LongitudinalDistanceSameDirectionOtherInFront") or (state.rss_state.longitudinalState.rssStateInformation.evaluator == "LongitudinalDistanceSameDirectionEgoFront")):
pygame.draw.polygon(display, (255, 255, 255), ((xpos+1, v_offset+1+4), (xpos+6, v_offset+1+0), (xpos+11, v_offset+1+4),
(xpos+7, v_offset+1+4), (xpos+7, v_offset+1+12), (xpos+5, v_offset+1+12), (xpos+5, v_offset+1+4)))
pygame.draw.polygon(
display, (
255, 255, 255), ((xpos + 1, v_offset + 1 + 4), (xpos + 6, v_offset + 1 + 0), (xpos + 11, v_offset + 1 + 4),
(xpos + 7, v_offset + 1 + 4), (xpos + 7, v_offset + 1 + 12), (xpos + 5, v_offset + 1 + 12), (xpos + 5, v_offset + 1 + 4)))
xpos += 14
if not state.rss_state.longitudinalState.isSafe and ((state.rss_state.longitudinalState.rssStateInformation.evaluator == "LongitudinalDistanceOppositeDirectionEgoCorrectLane") or (state.rss_state.longitudinalState.rssStateInformation.evaluator == "LongitudinalDistanceOppositeDirection")):
pygame.draw.polygon(display, (255, 255, 255), ((xpos+2, v_offset+1+8), (xpos+6, v_offset+1+12), (xpos+10, v_offset+1+8),
(xpos+7, v_offset+1+8), (xpos+7, v_offset+1+0), (xpos+5, v_offset+1+0), (xpos+5, v_offset+1+8)))
pygame.draw.polygon(
display, (
255, 255, 255), ((xpos + 2, v_offset + 1 + 8), (xpos + 6, v_offset + 1 + 12), (xpos + 10, v_offset + 1 + 8),
(xpos + 7, v_offset + 1 + 8), (xpos + 7, v_offset + 1 + 0), (xpos + 5, v_offset + 1 + 0), (xpos + 5, v_offset + 1 + 8)))
xpos += 14
if not state.rss_state.lateralStateRight.isSafe and not (state.rss_state.lateralStateRight.rssStateInformation.evaluator == "None"):
pygame.draw.polygon(display, (255, 255, 255), ((xpos+0, v_offset+1+4), (xpos+8, v_offset+1+4), (xpos+8, v_offset+1+1),
(xpos+12, v_offset+1+6), (xpos+8, v_offset+1+10), (xpos+8, v_offset+1+8), (xpos+0, v_offset+1+8)))
pygame.draw.polygon(
display, (
255, 255, 255), ((xpos + 0, v_offset + 1 + 4), (xpos + 8, v_offset + 1 + 4), (xpos + 8, v_offset + 1 + 1),
(xpos + 12, v_offset + 1 + 6), (xpos + 8, v_offset + 1 + 10), (xpos + 8, v_offset + 1 + 8), (xpos + 0, v_offset + 1 + 8)))
xpos += 14
if not state.rss_state.lateralStateLeft.isSafe and not (state.rss_state.lateralStateLeft.rssStateInformation.evaluator == "None"):
pygame.draw.polygon(display, (255, 255, 255), ((xpos+0, v_offset+1+6), (xpos+4, v_offset+1+1), (xpos+4, v_offset+1+4),
(xpos+12, v_offset+1+4), (xpos+12, v_offset+1+8), (xpos+4, v_offset+1+8), (xpos+4, v_offset+1+10)))
pygame.draw.polygon(
display, (
255, 255, 255), ((xpos + 0, v_offset + 1 + 6), (xpos + 4, v_offset + 1 + 1), (xpos + 4, v_offset + 1 + 4),
(xpos + 12, v_offset + 1 + 4), (xpos + 12, v_offset + 1 + 8), (xpos + 4, v_offset + 1 + 8), (xpos + 4, v_offset + 1 + 10)))
xpos += 14
elif state.actor_calculation_mode == rssmap.RssMode.Unstructured:
text = ""
@ -157,7 +165,7 @@ class RssUnstructuredSceneDrawer(object):
spawn_sensor = False
if mode == RssUnstructuredSceneDrawerMode.window:
self._dim = (self._display_dimensions[0]/3, self._display_dimensions[1]/2)
self._dim = (self._display_dimensions[0] / 3, self._display_dimensions[1] / 2)
spawn_sensor = True
elif mode == RssUnstructuredSceneDrawerMode.fullscreen:
self._dim = (self._display_dimensions[0], self._display_dimensions[1])
@ -204,9 +212,9 @@ class RssUnstructuredSceneDrawer(object):
pygame.draw.rect(surface, (0, 0, 0), rect, 0)
rect = pygame.Rect((0, 0), (surface.get_width(), 2))
pygame.draw.rect(surface, (0, 0, 0), rect, 0)
rect = pygame.Rect((0, surface.get_height()-2), (surface.get_width(), surface.get_height()))
rect = pygame.Rect((0, surface.get_height() - 2), (surface.get_width(), surface.get_height()))
pygame.draw.rect(surface, (0, 0, 0), rect, 0)
rect = pygame.Rect((surface.get_width()-2, 0), (surface.get_width(), surface.get_width()))
rect = pygame.Rect((surface.get_width() - 2, 0), (surface.get_width(), surface.get_width()))
pygame.draw.rect(surface, (0, 0, 0), rect, 0)
self._surface = surface
@ -262,7 +270,8 @@ class RssUnstructuredSceneDrawer(object):
for heading_range in allowed_heading_ranges:
polygons.append((RssUnstructuredSceneDrawer.transform_points(
RssUnstructuredSceneDrawer._get_points_from_pairs(
RssUnstructuredSceneDrawer.draw_heading_range(heading_range, rss_response.ego_dynamics_on_route)),
RssUnstructuredSceneDrawer.draw_heading_range(
heading_range, rss_response.ego_dynamics_on_route)),
self._camera.get_transform(), self._calibration), (0, 0, 255)))
RssUnstructuredSceneDrawer.draw_lines(surface, lines)
@ -687,8 +696,8 @@ class RssDebugDrawer(object):
self._world.debug.draw_arrow(heading_location_start, heading_location_end, 0.1, 0.1, color, 0.02, False)
sin_center = math.sin(float(ego_dynamics_on_route.route_heading) + math.pi/2.)
cos_center = math.cos(float(ego_dynamics_on_route.route_heading) + math.pi/2.)
sin_center = math.sin(float(ego_dynamics_on_route.route_heading) + math.pi / 2.)
cos_center = math.cos(float(ego_dynamics_on_route.route_heading) + math.pi / 2.)
center_location_start = self._player.get_location()
center_location_start.x -= cos_center * 2.
center_location_start.y += sin_center * 2.