New ConstantVelocityAgent and TM parameter (#5290)

This commit is contained in:
glopezdiest 2022-04-20 14:44:27 +02:00 committed by GitHub
parent 7646b326b8
commit 5003e58d7c
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
21 changed files with 266 additions and 24 deletions

View File

@ -1,5 +1,7 @@
## Latest ## Latest
* Added new ConstantVelocityAgent
* Added new parameter to the TrafficManager, `set_desired_speed`, to set a vehicle's speed.
* Added 4 new attributes to all vehicles: * Added 4 new attributes to all vehicles:
- `base_type` can be use as a vehicle classification. The possible values are *car*, *truck*, *van*, *motorcycle* and *bycicle*. - `base_type` can be use as a vehicle classification. The possible values are *car*, *truck*, *van*, *motorcycle* and *bycicle*.
- `special_type` provides more information about the vehicle. It is currently restricted to *electric*, *emergency* and *taxi*, and not all vehicles have this attribute filled. - `special_type` provides more information about the vehicle. It is currently restricted to *electric*, *emergency* and *taxi*, and not all vehicles have this attribute filled.

View File

@ -2424,6 +2424,11 @@ Sets the upper and lower boundaries for dormant actors to be respawned near the
- `upper_bound` (_float_) - The maximum distance in meters from the hero vehicle that a dormant actor will be respawned. - `upper_bound` (_float_) - The maximum distance in meters from the hero vehicle that a dormant actor will be respawned.
- **Warning:** <font color="#ED2F2F">_The `upper_bound` cannot be higher than the `actor_active_distance`. The `lower_bound` cannot be less than 25. - **Warning:** <font color="#ED2F2F">_The `upper_bound` cannot be higher than the `actor_active_distance`. The `lower_bound` cannot be less than 25.
_</font> _</font>
- <a name="carla.TrafficManager.set_desired_speed"></a>**<font color="#7fb800">set_desired_speed</font>**(<font color="#00a6ed">**self**</font>, <font color="#00a6ed">**actor**</font>, <font color="#00a6ed">**speed**</font>)
Sets the speed of a vehicle to the specified value.
- **Parameters:**
- `actor` (_[carla.Actor](#carla.Actor)_) - Vehicle whose speed is being changed.
- `speed` (_float_) - Desired speed at which the vehicle will move.
- <a name="carla.TrafficManager.set_global_distance_to_leading_vehicle"></a>**<font color="#7fb800">set_global_distance_to_leading_vehicle</font>**(<font color="#00a6ed">**self**</font>, <font color="#00a6ed">**distance**</font>) - <a name="carla.TrafficManager.set_global_distance_to_leading_vehicle"></a>**<font color="#7fb800">set_global_distance_to_leading_vehicle</font>**(<font color="#00a6ed">**self**</font>, <font color="#00a6ed">**distance**</font>)
Sets the minimum distance in meters that vehicles have to keep with the rest. The distance is in meters and will affect the minimum moving distance. It is computed from center to center of the vehicle objects. Sets the minimum distance in meters that vehicles have to keep with the rest. The distance is in meters and will affect the minimum moving distance. It is computed from center to center of the vehicle objects.
- **Parameters:** - **Parameters:**

View File

@ -31,8 +31,8 @@ static const double DELTA_TIME_BETWEEN_DESTRUCTIONS = 10.0;
} // namespace VehicleRemoval } // namespace VehicleRemoval
namespace HybridMode { namespace HybridMode {
static const float HYBRID_MODE_DT_FL = 0.1f; static const float HYBRID_MODE_DT_FL = 0.05f;
static const double HYBRID_MODE_DT = 0.1; static const double HYBRID_MODE_DT = 0.05;
static const double INV_HYBRID_DT = 1.0 / HYBRID_MODE_DT; static const double INV_HYBRID_DT = 1.0 / HYBRID_MODE_DT;
static const float PHYSICS_RADIUS = 50.0f; static const float PHYSICS_RADIUS = 50.0f;
} // namespace HybridMode } // namespace HybridMode

View File

@ -148,6 +148,7 @@ void LocalizationStage::Update(const unsigned long index) {
if (!recently_not_executed_lane_change) { if (!recently_not_executed_lane_change) {
float distance_frm_previous = cg::Math::DistanceSquared(last_lane_change_swpt.at(actor_id)->GetLocation(), vehicle_location); float distance_frm_previous = cg::Math::DistanceSquared(last_lane_change_swpt.at(actor_id)->GetLocation(), vehicle_location);
done_with_previous_lane_change = distance_frm_previous > lane_change_distance; done_with_previous_lane_change = distance_frm_previous > lane_change_distance;
if (done_with_previous_lane_change) last_lane_change_swpt.erase(actor_id);
} }
bool auto_or_force_lane_change = parameters.GetAutoLaneChange(actor_id) || force_lane_change; bool auto_or_force_lane_change = parameters.GetAutoLaneChange(actor_id) || force_lane_change;
bool front_waypoint_not_junction = !front_waypoint->CheckJunction(); bool front_waypoint_not_junction = !front_waypoint->CheckJunction();
@ -503,14 +504,20 @@ void LocalizationStage::ImportPath(Path &imported_path, Buffer &waypoint_buffer,
break; break;
} }
SimpleWaypointPtr next_wp_selection = next_waypoints.at(selection_index); SimpleWaypointPtr next_wp_selection = next_waypoints.at(selection_index);
PushWaypoint(actor_id, track_traffic, waypoint_buffer, next_wp_selection);
// Remove the imported waypoint from the path if it's close to the last one. // Remove the imported waypoint from the path if it's close to the last one.
if (next_wp_selection->DistanceSquared(imported) < 30.0f) { if (next_wp_selection->DistanceSquared(imported) < 30.0f) {
imported_path.erase(imported_path.begin()); imported_path.erase(imported_path.begin());
std::vector<SimpleWaypointPtr> possible_waypoints = next_wp_selection->GetNextWaypoint();
if (std::find(possible_waypoints.begin(), possible_waypoints.end(), imported) != possible_waypoints.end()) {
// If the lane is changing, only push the new waypoint
PushWaypoint(actor_id, track_traffic, waypoint_buffer, next_wp_selection);
}
PushWaypoint(actor_id, track_traffic, waypoint_buffer, imported); PushWaypoint(actor_id, track_traffic, waypoint_buffer, imported);
latest_imported = imported_path.front(); latest_imported = imported_path.front();
imported = local_map->GetWaypoint(latest_imported); imported = local_map->GetWaypoint(latest_imported);
} else {
PushWaypoint(actor_id, track_traffic, waypoint_buffer, next_wp_selection);
} }
} }
if (imported_path.empty()) { if (imported_path.empty()) {

View File

@ -44,6 +44,18 @@ void Parameters::SetPercentageSpeedDifference(const ActorPtr &actor, const float
float new_percentage = std::min(100.0f, percentage); float new_percentage = std::min(100.0f, percentage);
percentage_difference_from_speed_limit.AddEntry({actor->GetId(), new_percentage}); percentage_difference_from_speed_limit.AddEntry({actor->GetId(), new_percentage});
if (exact_desired_speed.Contains(actor->GetId())) {
exact_desired_speed.RemoveEntry(actor->GetId());
}
}
void Parameters::SetDesiredSpeed(const ActorPtr &actor, const float value) {
float new_value = std::max(0.0f, value);
exact_desired_speed.AddEntry({actor->GetId(), new_value});
if (percentage_difference_from_speed_limit.Contains(actor->GetId())) {
percentage_difference_from_speed_limit.RemoveEntry(actor->GetId());
}
} }
void Parameters::SetGlobalPercentageSpeedDifference(const float percentage) { void Parameters::SetGlobalPercentageSpeedDifference(const float percentage) {
@ -235,6 +247,8 @@ float Parameters::GetVehicleTargetVelocity(const ActorId &actor_id, const float
if (percentage_difference_from_speed_limit.Contains(actor_id)) { if (percentage_difference_from_speed_limit.Contains(actor_id)) {
percentage_difference = percentage_difference_from_speed_limit.GetValue(actor_id); percentage_difference = percentage_difference_from_speed_limit.GetValue(actor_id);
} else if (exact_desired_speed.Contains(actor_id)) {
return exact_desired_speed.GetValue(actor_id);
} }
return speed_limit * (1.0f - percentage_difference / 100.0f); return speed_limit * (1.0f - percentage_difference / 100.0f);

View File

@ -37,8 +37,10 @@ struct ChangeLaneInfo {
class Parameters { class Parameters {
private: private:
/// Target velocity map for individual vehicles. /// Target velocity map for individual vehicles, based on a % diffrerence from speed limit.
AtomicMap<ActorId, float> percentage_difference_from_speed_limit; AtomicMap<ActorId, float> percentage_difference_from_speed_limit;
/// Target velocity map for individual vehicles, based on a desired velocity.
AtomicMap<ActorId, float> exact_desired_speed;
/// Global target velocity limit % difference. /// Global target velocity limit % difference.
float global_percentage_difference_from_limit = 0; float global_percentage_difference_from_limit = 0;
/// Map containing a set of actors to be ignored during collision detection. /// Map containing a set of actors to be ignored during collision detection.
@ -104,6 +106,9 @@ public:
/// If less than 0, it's a % increase. /// If less than 0, it's a % increase.
void SetPercentageSpeedDifference(const ActorPtr &actor, const float percentage); void SetPercentageSpeedDifference(const ActorPtr &actor, const float percentage);
/// Set a vehicle's exact desired velocity.
void SetDesiredSpeed(const ActorPtr &actor, const float value);
/// Set a global % decrease in velocity with respect to the speed limit. /// Set a global % decrease in velocity with respect to the speed limit.
/// If less than 0, it's a % increase. /// If less than 0, it's a % increase.
void SetGlobalPercentageSpeedDifference(float const percentage); void SetGlobalPercentageSpeedDifference(float const percentage);

View File

@ -177,6 +177,14 @@ public:
} }
} }
/// Set a vehicle's exact desired velocity.
void SetDesiredSpeed(const ActorPtr &actor, const float value) {
TrafficManagerBase* tm_ptr = GetTM(_port);
if(tm_ptr != nullptr){
tm_ptr->SetDesiredSpeed(actor, value);
}
}
/// Set a global % decrease in velocity with respect to the speed limit. /// Set a global % decrease in velocity with respect to the speed limit.
/// If less than 0, it's a % increase. /// If less than 0, it's a % increase.
void SetGlobalPercentageSpeedDifference(float const percentage){ void SetGlobalPercentageSpeedDifference(float const percentage){

View File

@ -54,6 +54,9 @@ public:
/// If less than 0, it's a % increase. /// If less than 0, it's a % increase.
virtual void SetPercentageSpeedDifference(const ActorPtr &actor, const float percentage) = 0; virtual void SetPercentageSpeedDifference(const ActorPtr &actor, const float percentage) = 0;
/// Set a vehicle's exact desired velocity.
virtual void SetDesiredSpeed(const ActorPtr &actor, const float value) = 0;
/// Set a global % decrease in velocity with respect to the speed limit. /// Set a global % decrease in velocity with respect to the speed limit.
/// If less than 0, it's a % increase. /// If less than 0, it's a % increase.
virtual void SetGlobalPercentageSpeedDifference(float const percentage) = 0; virtual void SetGlobalPercentageSpeedDifference(float const percentage) = 0;

View File

@ -81,6 +81,12 @@ public:
_client->call("set_percentage_speed_difference", std::move(_actor), percentage); _client->call("set_percentage_speed_difference", std::move(_actor), percentage);
} }
/// Set a vehicle's exact desired velocity.
void SetDesiredSpeed(const carla::rpc::Actor &_actor, const float value) {
DEBUG_ASSERT(_client != nullptr);
_client->call("set_desired_speed", std::move(_actor), value);
}
/// Method to set a global % decrease in velocity with respect to the speed limit. /// Method to set a global % decrease in velocity with respect to the speed limit.
/// If less than 0, it's a % increase. /// If less than 0, it's a % increase.
void SetGlobalPercentageSpeedDifference(const float percentage) { void SetGlobalPercentageSpeedDifference(const float percentage) {

View File

@ -334,6 +334,10 @@ void TrafficManagerLocal::SetGlobalPercentageSpeedDifference(const float percent
parameters.SetGlobalPercentageSpeedDifference(percentage); parameters.SetGlobalPercentageSpeedDifference(percentage);
} }
void TrafficManagerLocal::SetDesiredSpeed(const ActorPtr &actor, const float value) {
parameters.SetDesiredSpeed(actor, value);
}
/// Method to set the automatic management of the vehicle lights /// Method to set the automatic management of the vehicle lights
void TrafficManagerLocal::SetUpdateVehicleLights(const ActorPtr &actor, const bool do_update) { void TrafficManagerLocal::SetUpdateVehicleLights(const ActorPtr &actor, const bool do_update) {
parameters.SetUpdateVehicleLights(actor, do_update); parameters.SetUpdateVehicleLights(actor, do_update);

View File

@ -161,6 +161,9 @@ public:
/// If less than 0, it's a % increase. /// If less than 0, it's a % increase.
void SetPercentageSpeedDifference(const ActorPtr &actor, const float percentage); void SetPercentageSpeedDifference(const ActorPtr &actor, const float percentage);
/// Set a vehicle's exact desired velocity.
void SetDesiredSpeed(const ActorPtr &actor, const float value);
/// Methos to set a global % decrease in velocity with respect to the speed limit. /// Methos to set a global % decrease in velocity with respect to the speed limit.
/// If less than 0, it's a % increase. /// If less than 0, it's a % increase.
void SetGlobalPercentageSpeedDifference(float const percentage); void SetGlobalPercentageSpeedDifference(float const percentage);

View File

@ -111,6 +111,12 @@ void TrafficManagerRemote::SetPercentageSpeedDifference(const ActorPtr &_actor,
client.SetPercentageSpeedDifference(actor, percentage); client.SetPercentageSpeedDifference(actor, percentage);
} }
void TrafficManagerRemote::SetDesiredSpeed(const ActorPtr &_actor, const float value) {
carla::rpc::Actor actor(_actor->Serialize());
client.SetDesiredSpeed(actor, value);
}
void TrafficManagerRemote::SetGlobalPercentageSpeedDifference(const float percentage) { void TrafficManagerRemote::SetGlobalPercentageSpeedDifference(const float percentage) {
client.SetGlobalPercentageSpeedDifference(percentage); client.SetGlobalPercentageSpeedDifference(percentage);
} }

View File

@ -57,6 +57,9 @@ public:
/// If less than 0, it's a % increase. /// If less than 0, it's a % increase.
void SetPercentageSpeedDifference(const ActorPtr &actor, const float percentage); void SetPercentageSpeedDifference(const ActorPtr &actor, const float percentage);
/// Set a vehicle's exact desired velocity.
void SetDesiredSpeed(const ActorPtr &actor, const float value);
/// Method to set a global % decrease in velocity with respect to the speed limit. /// Method to set a global % decrease in velocity with respect to the speed limit.
/// If less than 0, it's a % increase. /// If less than 0, it's a % increase.
void SetGlobalPercentageSpeedDifference(float const percentage); void SetGlobalPercentageSpeedDifference(float const percentage);

View File

@ -94,6 +94,11 @@ public:
tm->SetPercentageSpeedDifference(carla::client::detail::ActorVariant(actor).Get(tm->GetEpisodeProxy()), percentage); tm->SetPercentageSpeedDifference(carla::client::detail::ActorVariant(actor).Get(tm->GetEpisodeProxy()), percentage);
}); });
/// Set a vehicle's exact desired velocity.
server->bind("set_desired_speed", [=](carla::rpc::Actor actor, const float value) {
tm->SetDesiredSpeed(carla::client::detail::ActorVariant(actor).Get(tm->GetEpisodeProxy()), value);
});
/// Method to set the automatic management of the vehicle lights /// Method to set the automatic management of the vehicle lights
server->bind("update_vehicle_lights", [=](carla::rpc::Actor actor, const bool do_update) { server->bind("update_vehicle_lights", [=](carla::rpc::Actor actor, const bool do_update) {
tm->SetUpdateVehicleLights(carla::client::detail::ActorVariant(actor).Get(tm->GetEpisodeProxy()), do_update); tm->SetUpdateVehicleLights(carla::client::detail::ActorVariant(actor).Get(tm->GetEpisodeProxy()), do_update);

View File

@ -88,6 +88,7 @@ class BasicAgent(object):
Changes the target speed of the agent Changes the target speed of the agent
:param speed (float): target speed in Km/h :param speed (float): target speed in Km/h
""" """
self._target_speed = speed
self._local_planner.set_speed(speed) self._local_planner.set_speed(speed)
def follow_speed_limits(self, value=True): def follow_speed_limits(self, value=True):

View File

@ -30,16 +30,15 @@ class BehaviorAgent(BasicAgent):
are encoded in the agent, from cautious to a more aggressive ones. are encoded in the agent, from cautious to a more aggressive ones.
""" """
def __init__(self, vehicle, behavior='normal'): def __init__(self, vehicle, behavior='normal', opt_dict={}):
""" """
Constructor method. Constructor method.
:param vehicle: actor to apply to local planner logic onto :param vehicle: actor to apply to local planner logic onto
:param ignore_traffic_light: boolean to ignore any traffic light
:param behavior: type of agent to apply :param behavior: type of agent to apply
""" """
super(BehaviorAgent, self).__init__(vehicle) super(BehaviorAgent, self).__init__(vehicle, opt_dict=opt_dict)
self._look_ahead_steps = 0 self._look_ahead_steps = 0
# Vehicle information # Vehicle information

View File

@ -0,0 +1,121 @@
# Copyright (c) # Copyright (c) 2018-2020 CVC.
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
"""
This module implements an agent that roams around a track following random
waypoints and avoiding other vehicles. The agent also responds to traffic lights.
It can also make use of the global route planner to follow a specifed route
"""
import carla
from agents.navigation.basic_agent import BasicAgent
from agents.tools.misc import get_speed
class ConstantVelocityAgent(BasicAgent):
"""
ConstantVelocityAgent implements an agent that navigates the scene at a fixed velocity.
This agent will fail if asked to perform turns that are impossible are the desired speed.
This includes lane changes. When a collision is detected, the constant velocity will stop,
wait for a bit, and then start again.
"""
def __init__(self, vehicle, target_speed=20, opt_dict={}):
"""
Initialization the agent parameters, the local and the global planner.
:param vehicle: actor to apply to agent logic onto
:param target_speed: speed (in Km/h) at which the vehicle will move
:param opt_dict: dictionary in case some of its parameters want to be changed.
This also applies to parameters related to the LocalPlanner.
"""
super(ConstantVelocityAgent, self).__init__(vehicle, target_speed, opt_dict=opt_dict)
self._use_basic_behavior = False # Whether or not to use the BasicAgent behavior when the constant velocity is down
self._target_speed = target_speed / 3.6 # [m/s]
self._current_speed = vehicle.get_velocity().length() # [m/s]
self._constant_velocity_stop_time = None
self._restart_time = float('inf') # Time after collision before the constant velocity behavior starts again
if 'restart_time' in opt_dict:
self._restart_time = opt_dict['restart_time']
if 'use_basic_behavior' in opt_dict:
self._use_basic_behavior = opt_dict['use_basic_behavior']
if 'force_lane_following' in opt_dict:
self._force_lane_following = opt_dict['force_lane_following']
self.is_constant_velocity_active = True
self._set_collision_sensor()
self._set_constant_velocity(target_speed)
def set_target_speed(self, speed):
"""Changes the target speed of the agent"""
self._target_speed = speed / 3.6
self._local_planner.set_speed(speed)
def stop_constant_velocity(self):
"""Stops the constant velocity behavior"""
self.is_constant_velocity_active = False
self._vehicle.disable_constant_velocity()
self._constant_velocity_stop_time = self._world.get_snapshot().timestamp.elapsed_seconds
def restart_constant_velocity(self):
"""Public method to restart the constant velocity"""
self.is_constant_velocity_active = True
self._set_constant_velocity(self._target_speed)
def _set_constant_velocity(self, speed):
"""Forces the agent to drive at the specified speed"""
self._vehicle.enable_constant_velocity(carla.Vector3D(speed, 0, 0))
def run_step(self):
"""Execute one step of navigation."""
if not self.is_constant_velocity_active:
if self._world.get_snapshot().timestamp.elapsed_seconds - self._constant_velocity_stop_time > self._restart_time:
self.restart_constant_velocity()
self.is_constant_velocity_active = True
elif self._use_basic_behavior:
return super(ConstantVelocityAgent, self).run_step()
else:
return carla.VehicleControl()
hazard_detected = False
# Retrieve all relevant actors
actor_list = self._world.get_actors()
vehicle_list = actor_list.filter("*vehicle*")
lights_list = actor_list.filter("*traffic_light*")
vehicle_speed = self._vehicle.get_velocity().length()
max_vehicle_distance = self._base_vehicle_threshold + vehicle_speed
affected_by_vehicle, adversary, _ = self._vehicle_obstacle_detected(vehicle_list, max_vehicle_distance)
if affected_by_vehicle:
vehicle_velocity = self._vehicle.get_velocity()
hazard_speed = vehicle_velocity.dot(adversary.get_velocity()) / vehicle_velocity.length()
hazard_detected = True
# Check if the vehicle is affected by a red traffic light
max_tlight_distance = self._base_tlight_threshold + 0.3 * vehicle_speed
affected_by_tlight, _ = self._affected_by_traffic_light(lights_list, max_tlight_distance)
if affected_by_tlight:
hazard_speed = 0
hazard_detected = True
# The longitudinal PID is overwritten by the constant velocity but it is
# still useful to apply it so that the vehicle isn't moving with static wheels
control = self._local_planner.run_step()
if hazard_detected:
self._set_constant_velocity(hazard_speed)
else:
self._set_constant_velocity(self._target_speed)
return control
def _set_collision_sensor(self):
blueprint = self._world.get_blueprint_library().find('sensor.other.collision')
self._collision_sensor = self._world.spawn_actor(blueprint, carla.Transform(), attach_to=self._vehicle)
self._collision_sensor.listen(lambda event: self.stop_constant_velocity())

View File

@ -77,6 +77,7 @@ class LocalPlanner(object):
self._max_steer = 0.8 self._max_steer = 0.8
self._offset = 0 self._offset = 0
self._base_min_distance = 3.0 self._base_min_distance = 3.0
self._distance_ratio = 0.5
self._follow_speed_limits = False self._follow_speed_limits = False
# Overload parameters # Overload parameters
@ -101,6 +102,8 @@ class LocalPlanner(object):
self._offset = opt_dict['offset'] self._offset = opt_dict['offset']
if 'base_min_distance' in opt_dict: if 'base_min_distance' in opt_dict:
self._base_min_distance = opt_dict['base_min_distance'] self._base_min_distance = opt_dict['base_min_distance']
if 'distance_ratio' in opt_dict:
self._distance_ratio = opt_dict['distance_ratio']
if 'follow_speed_limits' in opt_dict: if 'follow_speed_limits' in opt_dict:
self._follow_speed_limits = opt_dict['follow_speed_limits'] self._follow_speed_limits = opt_dict['follow_speed_limits']
@ -223,7 +226,7 @@ class LocalPlanner(object):
# Purge the queue of obsolete waypoints # Purge the queue of obsolete waypoints
veh_location = self._vehicle.get_location() veh_location = self._vehicle.get_location()
vehicle_speed = get_speed(self._vehicle) / 3.6 vehicle_speed = get_speed(self._vehicle) / 3.6
self._min_distance = self._base_min_distance + 0.5 *vehicle_speed self._min_distance = self._base_min_distance + self._distance_ratio * vehicle_speed
num_waypoint_removed = 0 num_waypoint_removed = 0
for waypoint, _ in self._waypoints_queue: for waypoint, _ in self._waypoints_queue:

View File

@ -87,6 +87,7 @@ void export_trafficmanager() {
class_<ctm::TrafficManager>("TrafficManager", no_init) class_<ctm::TrafficManager>("TrafficManager", no_init)
.def("get_port", &ctm::TrafficManager::Port) .def("get_port", &ctm::TrafficManager::Port)
.def("vehicle_percentage_speed_difference", &ctm::TrafficManager::SetPercentageSpeedDifference) .def("vehicle_percentage_speed_difference", &ctm::TrafficManager::SetPercentageSpeedDifference)
.def("set_desired_speed", &ctm::TrafficManager::SetDesiredSpeed)
.def("global_percentage_speed_difference", &ctm::TrafficManager::SetGlobalPercentageSpeedDifference) .def("global_percentage_speed_difference", &ctm::TrafficManager::SetGlobalPercentageSpeedDifference)
.def("update_vehicle_lights", &ctm::TrafficManager::SetUpdateVehicleLights) .def("update_vehicle_lights", &ctm::TrafficManager::SetUpdateVehicleLights)
.def("collision_detection", &ctm::TrafficManager::SetCollisionDetection) .def("collision_detection", &ctm::TrafficManager::SetCollisionDetection)

View File

@ -512,6 +512,19 @@
doc: > doc: >
Sets the minimum distance in meters that vehicles have to keep with the rest. The distance is in meters and will affect the minimum moving distance. It is computed from center to center of the vehicle objects. Sets the minimum distance in meters that vehicles have to keep with the rest. The distance is in meters and will affect the minimum moving distance. It is computed from center to center of the vehicle objects.
# -------------------------------------- # --------------------------------------
- def_name: set_desired_speed
params:
- param_name: actor
type: carla.Actor
doc: >
Vehicle whose speed is being changed.
- param_name: speed
type: float
doc: >
Desired speed at which the vehicle will move.
doc: >
Sets the speed of a vehicle to the specified value.
# --------------------------------------
- def_name: set_hybrid_physics_mode - def_name: set_hybrid_physics_mode
params: params:
- param_name: enabled - param_name: enabled

View File

@ -60,6 +60,7 @@ from carla import ColorConverter as cc
from agents.navigation.behavior_agent import BehaviorAgent # pylint: disable=import-error from agents.navigation.behavior_agent import BehaviorAgent # pylint: disable=import-error
from agents.navigation.basic_agent import BasicAgent # pylint: disable=import-error from agents.navigation.basic_agent import BasicAgent # pylint: disable=import-error
from agents.navigation.constant_velocity_agent import ConstantVelocityAgent # pylint: disable=import-error
# ============================================================================== # ==============================================================================
@ -80,6 +81,29 @@ def get_actor_display_name(actor, truncate=250):
name = ' '.join(actor.type_id.replace('_', '.').title().split('.')[1:]) name = ' '.join(actor.type_id.replace('_', '.').title().split('.')[1:])
return (name[:truncate - 1] + u'\u2026') if len(name) > truncate else name return (name[:truncate - 1] + u'\u2026') if len(name) > truncate else name
def get_actor_blueprints(world, filter, generation):
bps = world.get_blueprint_library().filter(filter)
if generation.lower() == "all":
return bps
# If the filter returns only one bp, we assume that this one needed
# and therefore, we ignore the generation
if len(bps) == 1:
return bps
try:
int_generation = int(generation)
# Check if generation is in available generations
if int_generation in [1, 2]:
bps = [x for x in bps if int(x.get_attribute('generation')) == int_generation]
return bps
else:
print(" Warning! Actor Generation is not valid. No actor will be spawned.")
return []
except:
print(" Warning! Actor Generation is not valid. No actor will be spawned.")
return []
# ============================================================================== # ==============================================================================
# -- World --------------------------------------------------------------- # -- World ---------------------------------------------------------------
@ -108,6 +132,7 @@ class World(object):
self._weather_presets = find_weather_presets() self._weather_presets = find_weather_presets()
self._weather_index = 0 self._weather_index = 0
self._actor_filter = args.filter self._actor_filter = args.filter
self._actor_generation = args.generation
self.restart(args) self.restart(args)
self.world.on_tick(hud.on_world_tick) self.world.on_tick(hud.on_world_tick)
self.recording_enabled = False self.recording_enabled = False
@ -120,7 +145,7 @@ class World(object):
cam_pos_id = self.camera_manager.transform_index if self.camera_manager is not None else 0 cam_pos_id = self.camera_manager.transform_index if self.camera_manager is not None else 0
# Get a random blueprint. # Get a random blueprint.
blueprint = random.choice(self.world.get_blueprint_library().filter(self._actor_filter)) blueprint = random.choice(get_actor_blueprints(self.world, self._actor_filter, self._actor_generation))
blueprint.set_attribute('role_name', 'hero') blueprint.set_attribute('role_name', 'hero')
if blueprint.has_attribute('color'): if blueprint.has_attribute('color'):
color = random.choice(blueprint.get_attribute('color').recommended_values) color = random.choice(blueprint.get_attribute('color').recommended_values)
@ -566,19 +591,17 @@ class CameraManager(object):
self._parent = parent_actor self._parent = parent_actor
self.hud = hud self.hud = hud
self.recording = False self.recording = False
bound_x = 0.5 + self._parent.bounding_box.extent.x
bound_y = 0.5 + self._parent.bounding_box.extent.y bound_y = 0.5 + self._parent.bounding_box.extent.y
bound_z = 0.5 + self._parent.bounding_box.extent.z
attachment = carla.AttachmentType attachment = carla.AttachmentType
self._camera_transforms = [ self._camera_transforms = [
(carla.Transform( (carla.Transform(carla.Location(x=-2.0*bound_x, y=+0.0*bound_y, z=2.0*bound_z), carla.Rotation(pitch=8.0)), attachment.SpringArm),
carla.Location(x=-5.5, z=2.5), carla.Rotation(pitch=8.0)), attachment.SpringArm), (carla.Transform(carla.Location(x=+0.8*bound_x, y=+0.0*bound_y, z=1.3*bound_z)), attachment.Rigid),
(carla.Transform( (carla.Transform(carla.Location(x=+1.9*bound_x, y=+1.0*bound_y, z=1.2*bound_z)), attachment.SpringArm),
carla.Location(x=1.6, z=1.7)), attachment.Rigid), (carla.Transform(carla.Location(x=-2.8*bound_x, y=+0.0*bound_y, z=4.6*bound_z), carla.Rotation(pitch=6.0)), attachment.SpringArm),
(carla.Transform( (carla.Transform(carla.Location(x=-1.0, y=-1.0*bound_y, z=0.4*bound_z)), attachment.Rigid)]
carla.Location(x=5.5, y=1.5, z=1.5)), attachment.SpringArm),
(carla.Transform(
carla.Location(x=-8.0, z=6.0), carla.Rotation(pitch=6.0)), attachment.SpringArm),
(carla.Transform(
carla.Location(x=-1, y=-bound_y, z=0.5)), attachment.Rigid)]
self.transform_index = 1 self.transform_index = 1
self.sensors = [ self.sensors = [
['sensor.camera.rgb', cc.Raw, 'Camera RGB'], ['sensor.camera.rgb', cc.Raw, 'Camera RGB'],
@ -712,8 +735,13 @@ def game_loop(args):
world = World(client.get_world(), hud, args) world = World(client.get_world(), hud, args)
controller = KeyboardControl(world) controller = KeyboardControl(world)
if args.agent == "Basic": if args.agent == "Basic":
agent = BasicAgent(world.player) agent = BasicAgent(world.player, 30)
else: elif args.agent == "Constant":
agent = ConstantVelocityAgent(world.player, 30)
ground_loc = world.world.ground_projection(world.player.get_location(), 5)
if ground_loc:
world.player.set_location(ground_loc.location + carla.Location(z=0.01))
elif args.agent == "Behavior":
agent = BehaviorAgent(world.player, behavior=args.behavior) agent = BehaviorAgent(world.player, behavior=args.behavior)
# Set the agent destination # Set the agent destination
@ -739,7 +767,7 @@ def game_loop(args):
if agent.done(): if agent.done():
if args.loop: if args.loop:
agent.set_destination(random.choice(spawn_points).location) agent.set_destination(random.choice(spawn_points).location)
world.hud.notification("The target has been reached, searching for another target", seconds=4.0) world.hud.notification("Target reached", seconds=4.0)
print("The target has been reached, searching for another target") print("The target has been reached, searching for another target")
else: else:
print("The target has been reached, stopping the simulation") print("The target has been reached, stopping the simulation")
@ -803,6 +831,11 @@ def main():
metavar='PATTERN', metavar='PATTERN',
default='vehicle.*', default='vehicle.*',
help='Actor filter (default: "vehicle.*")') help='Actor filter (default: "vehicle.*")')
argparser.add_argument(
'--generation',
metavar='G',
default='2',
help='restrict to certain actor generation (values: "1","2","All" - default: "2")')
argparser.add_argument( argparser.add_argument(
'-l', '--loop', '-l', '--loop',
action='store_true', action='store_true',
@ -810,7 +843,7 @@ def main():
help='Sets a new random destination upon reaching the previous one (default: False)') help='Sets a new random destination upon reaching the previous one (default: False)')
argparser.add_argument( argparser.add_argument(
"-a", "--agent", type=str, "-a", "--agent", type=str,
choices=["Behavior", "Basic"], choices=["Behavior", "Basic", "Constant"],
help="select which agent to run", help="select which agent to run",
default="Behavior") default="Behavior")
argparser.add_argument( argparser.add_argument(