Windows compatibility changes
This commit is contained in:
parent
9d068d2be2
commit
3c1aa7d847
|
@ -27,7 +27,7 @@ namespace traffic_manager {
|
||||||
void BatchControlStage::Action() {
|
void BatchControlStage::Action() {
|
||||||
|
|
||||||
// Looping over registered actors.
|
// Looping over registered actors.
|
||||||
for (uint i = 0u; i < number_of_vehicles; ++i) {
|
for (uint64_t i = 0u; i < number_of_vehicles; ++i) {
|
||||||
|
|
||||||
cr::VehicleControl vehicle_control;
|
cr::VehicleControl vehicle_control;
|
||||||
|
|
||||||
|
|
|
@ -40,7 +40,7 @@ namespace traffic_manager {
|
||||||
/// Array to hold command batch.
|
/// Array to hold command batch.
|
||||||
std::shared_ptr<std::vector<cr::Command>> commands;
|
std::shared_ptr<std::vector<cr::Command>> commands;
|
||||||
/// Number of vehicles registered with the traffic manager.
|
/// Number of vehicles registered with the traffic manager.
|
||||||
uint number_of_vehicles;
|
uint64_t number_of_vehicles;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
|
||||||
|
|
|
@ -98,7 +98,7 @@ namespace CollisionStageConstants {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Looping over registered actors.
|
// Looping over registered actors.
|
||||||
for (uint i = 0u; i < number_of_vehicles; ++i) {
|
for (uint64_t i = 0u; i < number_of_vehicles; ++i) {
|
||||||
|
|
||||||
const LocalizationToCollisionData &data = localization_frame->at(i);
|
const LocalizationToCollisionData &data = localization_frame->at(i);
|
||||||
const Actor ego_actor = data.actor;
|
const Actor ego_actor = data.actor;
|
||||||
|
@ -165,7 +165,7 @@ namespace CollisionStageConstants {
|
||||||
// This map also provides us the additional benefit of being able to
|
// This map also provides us the additional benefit of being able to
|
||||||
// quickly identify
|
// quickly identify
|
||||||
// if a vehicle id is registered with the traffic manager or not.
|
// if a vehicle id is registered with the traffic manager or not.
|
||||||
uint index = 0u;
|
uint64_t index = 0u;
|
||||||
for (auto &element: *localization_frame.get()) {
|
for (auto &element: *localization_frame.get()) {
|
||||||
vehicle_id_to_index.insert({element.actor->GetId(), index++});
|
vehicle_id_to_index.insert({element.actor->GetId(), index++});
|
||||||
}
|
}
|
||||||
|
@ -301,7 +301,7 @@ namespace CollisionStageConstants {
|
||||||
const float length = vehicle->GetBoundingBox().extent.x;
|
const float length = vehicle->GetBoundingBox().extent.x;
|
||||||
|
|
||||||
SimpleWaypointPtr boundary_start = waypoint_buffer.front();
|
SimpleWaypointPtr boundary_start = waypoint_buffer.front();
|
||||||
uint boundary_start_index = 0u;
|
uint64_t boundary_start_index = 0u;
|
||||||
while (boundary_start->DistanceSquared(vehicle_location) < std::pow(length, 2) &&
|
while (boundary_start->DistanceSquared(vehicle_location) < std::pow(length, 2) &&
|
||||||
boundary_start_index < waypoint_buffer.size() -1) {
|
boundary_start_index < waypoint_buffer.size() -1) {
|
||||||
boundary_start = waypoint_buffer.at(boundary_start_index);
|
boundary_start = waypoint_buffer.at(boundary_start_index);
|
||||||
|
@ -314,7 +314,7 @@ namespace CollisionStageConstants {
|
||||||
// At non-signalized junctions, we extend the boundary across the junction
|
// At non-signalized junctions, we extend the boundary across the junction
|
||||||
// and in all other situations, boundary length is velocity-dependent.
|
// and in all other situations, boundary length is velocity-dependent.
|
||||||
bool reached_distance = false;
|
bool reached_distance = false;
|
||||||
for (uint j = boundary_start_index; !reached_distance && (j < waypoint_buffer.size()); ++j) {
|
for (uint64_t j = boundary_start_index; !reached_distance && (j < waypoint_buffer.size()); ++j) {
|
||||||
|
|
||||||
if (boundary_start->DistanceSquared(current_point) > std::pow(bbox_extension, 2)) {
|
if (boundary_start->DistanceSquared(current_point) > std::pow(bbox_extension, 2)) {
|
||||||
reached_distance = true;
|
reached_distance = true;
|
||||||
|
@ -432,7 +432,7 @@ namespace CollisionStageConstants {
|
||||||
}
|
}
|
||||||
|
|
||||||
void CollisionStage::DrawBoundary(const LocationList &boundary) const {
|
void CollisionStage::DrawBoundary(const LocationList &boundary) const {
|
||||||
for (uint i = 0u; i < boundary.size(); ++i) {
|
for (uint64_t i = 0u; i < boundary.size(); ++i) {
|
||||||
debug_helper.DrawLine(
|
debug_helper.DrawLine(
|
||||||
boundary[i] + cg::Location(0.0f, 0.0f, 1.0f),
|
boundary[i] + cg::Location(0.0f, 0.0f, 1.0f),
|
||||||
boundary[(i + 1) % boundary.size()] + cg::Location(0.0f, 0.0f, 1.0f),
|
boundary[(i + 1) % boundary.size()] + cg::Location(0.0f, 0.0f, 1.0f),
|
||||||
|
|
|
@ -83,9 +83,9 @@ namespace traffic_manager {
|
||||||
std::unordered_map<ActorId, Actor> unregistered_actors;
|
std::unordered_map<ActorId, Actor> unregistered_actors;
|
||||||
/// An object used to keep track of time between checking for all world
|
/// An object used to keep track of time between checking for all world
|
||||||
/// actors.
|
/// actors.
|
||||||
chr::time_point<chr::_V2::system_clock, chr::nanoseconds> last_world_actors_pass_instance;
|
chr::time_point<chr::system_clock, chr::nanoseconds> last_world_actors_pass_instance;
|
||||||
/// Number of vehicles registered with the traffic manager.
|
/// Number of vehicles registered with the traffic manager.
|
||||||
uint number_of_vehicles;
|
uint64_t number_of_vehicles;
|
||||||
|
|
||||||
/// Returns the bounding box corners of the vehicle passed to the method.
|
/// Returns the bounding box corners of the vehicle passed to the method.
|
||||||
LocationList GetBoundary(const Actor &actor) const;
|
LocationList GetBoundary(const Actor &actor) const;
|
||||||
|
|
|
@ -13,7 +13,7 @@ namespace MapConstants {
|
||||||
// Very important that this is less than 10^-4.
|
// Very important that this is less than 10^-4.
|
||||||
static const float ZERO_LENGTH = 0.0001f;
|
static const float ZERO_LENGTH = 0.0001f;
|
||||||
static const float INFINITE_DISTANCE = std::numeric_limits<float>::max();
|
static const float INFINITE_DISTANCE = std::numeric_limits<float>::max();
|
||||||
static const uint LANE_CHANGE_LOOK_AHEAD = 5u;
|
static const uint64_t LANE_CHANGE_LOOK_AHEAD = 5u;
|
||||||
// Cosine of the angle.
|
// Cosine of the angle.
|
||||||
static const float LANE_CHANGE_ANGULAR_THRESHOLD = 0.5f;
|
static const float LANE_CHANGE_ANGULAR_THRESHOLD = 0.5f;
|
||||||
static const float GRID_SIZE = 4.0f;
|
static const float GRID_SIZE = 4.0f;
|
||||||
|
@ -76,7 +76,7 @@ namespace MapConstants {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Linking segments.
|
// Linking segments.
|
||||||
uint i = 0u, j = 0u;
|
uint64_t i = 0u, j = 0u;
|
||||||
for (SimpleWaypointPtr end_point : exit_node_list) {
|
for (SimpleWaypointPtr end_point : exit_node_list) {
|
||||||
for (SimpleWaypointPtr begin_point : entry_node_list) {
|
for (SimpleWaypointPtr begin_point : entry_node_list) {
|
||||||
if (end_point->DistanceSquared(begin_point) < square(ZERO_LENGTH) and i != j) {
|
if (end_point->DistanceSquared(begin_point) < square(ZERO_LENGTH) and i != j) {
|
||||||
|
@ -110,7 +110,7 @@ namespace MapConstants {
|
||||||
relative_vector = relative_vector.MakeUnitVector();
|
relative_vector = relative_vector.MakeUnitVector();
|
||||||
const float relative_dot = cg::Math::Dot(end_point_vector, relative_vector);
|
const float relative_dot = cg::Math::Dot(end_point_vector, relative_vector);
|
||||||
if (relative_dot < LANE_CHANGE_ANGULAR_THRESHOLD) {
|
if (relative_dot < LANE_CHANGE_ANGULAR_THRESHOLD) {
|
||||||
uint count = LANE_CHANGE_LOOK_AHEAD;
|
uint64_t count = LANE_CHANGE_LOOK_AHEAD;
|
||||||
while (count > 0u) {
|
while (count > 0u) {
|
||||||
closest_connection = closest_connection->GetNextWaypoint()[0];
|
closest_connection = closest_connection->GetNextWaypoint()[0];
|
||||||
--count;
|
--count;
|
||||||
|
|
|
@ -70,7 +70,7 @@ namespace LocalizationConstants {
|
||||||
traffic_light_frame_selector ? traffic_light_frame_a : traffic_light_frame_b;
|
traffic_light_frame_selector ? traffic_light_frame_a : traffic_light_frame_b;
|
||||||
|
|
||||||
// Looping over registered actors.
|
// Looping over registered actors.
|
||||||
for (uint i = 0u; i < actor_list.size(); ++i) {
|
for (uint64_t i = 0u; i < actor_list.size(); ++i) {
|
||||||
|
|
||||||
const Actor vehicle = actor_list.at(i);
|
const Actor vehicle = actor_list.at(i);
|
||||||
const ActorId actor_id = vehicle->GetId();
|
const ActorId actor_id = vehicle->GetId();
|
||||||
|
@ -125,7 +125,7 @@ namespace LocalizationConstants {
|
||||||
|
|
||||||
if (change_over_point != nullptr) {
|
if (change_over_point != nullptr) {
|
||||||
auto number_of_pops = waypoint_buffer.size();
|
auto number_of_pops = waypoint_buffer.size();
|
||||||
for (uint j = 0u; j < number_of_pops; ++j) {
|
for (uint64_t j = 0u; j < number_of_pops; ++j) {
|
||||||
PopWaypoint(waypoint_buffer, actor_id);
|
PopWaypoint(waypoint_buffer, actor_id);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -138,7 +138,7 @@ namespace LocalizationConstants {
|
||||||
<= std::pow(horizon_size, 2)) {
|
<= std::pow(horizon_size, 2)) {
|
||||||
|
|
||||||
std::vector<SimpleWaypointPtr> next_waypoints = waypoint_buffer.back()->GetNextWaypoint();
|
std::vector<SimpleWaypointPtr> next_waypoints = waypoint_buffer.back()->GetNextWaypoint();
|
||||||
uint selection_index = 0u;
|
uint64_t selection_index = 0u;
|
||||||
// Pseudo-randomized path selection if found more than one choice.
|
// Pseudo-randomized path selection if found more than one choice.
|
||||||
if (next_waypoints.size() > 1) {
|
if (next_waypoints.size() > 1) {
|
||||||
selection_index = static_cast<uint>(rand()) % next_waypoints.size();
|
selection_index = static_cast<uint>(rand()) % next_waypoints.size();
|
||||||
|
@ -151,7 +151,7 @@ namespace LocalizationConstants {
|
||||||
const float target_point_distance = std::max(std::ceil(vehicle_velocity * TARGET_WAYPOINT_TIME_HORIZON),
|
const float target_point_distance = std::max(std::ceil(vehicle_velocity * TARGET_WAYPOINT_TIME_HORIZON),
|
||||||
TARGET_WAYPOINT_HORIZON_LENGTH);
|
TARGET_WAYPOINT_HORIZON_LENGTH);
|
||||||
SimpleWaypointPtr target_waypoint = waypoint_buffer.front();
|
SimpleWaypointPtr target_waypoint = waypoint_buffer.front();
|
||||||
for (uint j = 0u;
|
for (uint64_t j = 0u;
|
||||||
(j < waypoint_buffer.size()) &&
|
(j < waypoint_buffer.size()) &&
|
||||||
(waypoint_buffer.front()->DistanceSquared(target_waypoint)
|
(waypoint_buffer.front()->DistanceSquared(target_waypoint)
|
||||||
< std::pow(target_point_distance, 2));
|
< std::pow(target_point_distance, 2));
|
||||||
|
@ -176,8 +176,8 @@ namespace LocalizationConstants {
|
||||||
const float look_ahead_distance = std::max(2.0f * vehicle_velocity, MINIMUM_JUNCTION_LOOK_AHEAD);
|
const float look_ahead_distance = std::max(2.0f * vehicle_velocity, MINIMUM_JUNCTION_LOOK_AHEAD);
|
||||||
|
|
||||||
SimpleWaypointPtr look_ahead_point = waypoint_buffer.front();
|
SimpleWaypointPtr look_ahead_point = waypoint_buffer.front();
|
||||||
uint look_ahead_index = 0u;
|
uint64_t look_ahead_index = 0u;
|
||||||
for (uint j = 0u;
|
for (uint64_t j = 0u;
|
||||||
(waypoint_buffer.front()->DistanceSquared(look_ahead_point)
|
(waypoint_buffer.front()->DistanceSquared(look_ahead_point)
|
||||||
< std::pow(look_ahead_distance, 2)) &&
|
< std::pow(look_ahead_distance, 2)) &&
|
||||||
(j < waypoint_buffer.size());
|
(j < waypoint_buffer.size());
|
||||||
|
@ -189,7 +189,7 @@ namespace LocalizationConstants {
|
||||||
bool approaching_junction = false;
|
bool approaching_junction = false;
|
||||||
if (waypoint_buffer.front()->CheckJunction() || (look_ahead_point->CheckJunction() && !(waypoint_buffer.front()->CheckJunction()))) {
|
if (waypoint_buffer.front()->CheckJunction() || (look_ahead_point->CheckJunction() && !(waypoint_buffer.front()->CheckJunction()))) {
|
||||||
if (speed_limit > HIGHWAY_SPEED) {
|
if (speed_limit > HIGHWAY_SPEED) {
|
||||||
for (uint j = 0u; (j < look_ahead_index) && !approaching_junction; ++j) {
|
for (uint64_t j = 0u; (j < look_ahead_index) && !approaching_junction; ++j) {
|
||||||
SimpleWaypointPtr swp = waypoint_buffer.at(j);
|
SimpleWaypointPtr swp = waypoint_buffer.at(j);
|
||||||
if (swp->GetNextWaypoint().size() > 1) {
|
if (swp->GetNextWaypoint().size() > 1) {
|
||||||
approaching_junction = true;
|
approaching_junction = true;
|
||||||
|
@ -264,7 +264,7 @@ namespace LocalizationConstants {
|
||||||
|
|
||||||
actor_list = registered_actors.GetList();
|
actor_list = registered_actors.GetList();
|
||||||
|
|
||||||
uint index = 0u;
|
uint64_t index = 0u;
|
||||||
for (auto &actor: actor_list) {
|
for (auto &actor: actor_list) {
|
||||||
|
|
||||||
vehicle_id_to_index.insert({actor->GetId(), index});
|
vehicle_id_to_index.insert({actor->GetId(), index});
|
||||||
|
@ -339,7 +339,7 @@ namespace LocalizationConstants {
|
||||||
|
|
||||||
void LocalizationStage::DrawBuffer(Buffer &buffer) {
|
void LocalizationStage::DrawBuffer(Buffer &buffer) {
|
||||||
|
|
||||||
for (uint i = 0u; i < buffer.size() && i < 5; ++i) {
|
for (uint64_t i = 0u; i < buffer.size() && i < 5; ++i) {
|
||||||
debug_helper.DrawPoint(buffer.at(i)->GetLocation(), 0.1f, {255u, 0u, 0u}, 0.5f);
|
debug_helper.DrawPoint(buffer.at(i)->GetLocation(), 0.1f, {255u, 0u, 0u}, 0.5f);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -91,7 +91,7 @@ namespace traffic_manager {
|
||||||
/// Map connecting actor ids to indices of data arrays.
|
/// Map connecting actor ids to indices of data arrays.
|
||||||
std::unordered_map<ActorId, uint> vehicle_id_to_index;
|
std::unordered_map<ActorId, uint> vehicle_id_to_index;
|
||||||
/// Number of vehicles currently registered with the traffic manager.
|
/// Number of vehicles currently registered with the traffic manager.
|
||||||
uint number_of_vehicles;
|
uint64_t number_of_vehicles;
|
||||||
/// Used to only calculate the extended buffer once at junctions
|
/// Used to only calculate the extended buffer once at junctions
|
||||||
std::map<carla::ActorId, bool> approached;
|
std::map<carla::ActorId, bool> approached;
|
||||||
/// Final Waypoint of the bounding box at intersections, amps to their respective IDs
|
/// Final Waypoint of the bounding box at intersections, amps to their respective IDs
|
||||||
|
@ -99,7 +99,7 @@ namespace traffic_manager {
|
||||||
/// Object for tracking paths of the traffic vehicles.
|
/// Object for tracking paths of the traffic vehicles.
|
||||||
TrackTraffic track_traffic;
|
TrackTraffic track_traffic;
|
||||||
/// Map of all vehicles' idle time
|
/// Map of all vehicles' idle time
|
||||||
std::unordered_map<ActorId, chr::time_point<chr::_V2::system_clock, chr::nanoseconds>> idle_time;
|
std::unordered_map<ActorId, chr::time_point<chr::system_clock, chr::nanoseconds>> idle_time;
|
||||||
|
|
||||||
/// A simple method used to draw waypoint buffer ahead of a vehicle.
|
/// A simple method used to draw waypoint buffer ahead of a vehicle.
|
||||||
void DrawBuffer(Buffer &buffer);
|
void DrawBuffer(Buffer &buffer);
|
||||||
|
|
|
@ -63,7 +63,7 @@ namespace PlannerConstants {
|
||||||
const auto current_control_frame = frame_selector ? control_frame_a : control_frame_b;
|
const auto current_control_frame = frame_selector ? control_frame_a : control_frame_b;
|
||||||
|
|
||||||
// Looping over all vehicles.
|
// Looping over all vehicles.
|
||||||
for (uint i = 0u; i < number_of_vehicles; ++i) {
|
for (uint64_t i = 0u; i < number_of_vehicles; ++i) {
|
||||||
|
|
||||||
const LocalizationToPlannerData &localization_data = localization_frame->at(i);
|
const LocalizationToPlannerData &localization_data = localization_frame->at(i);
|
||||||
const Actor actor = localization_data.actor;
|
const Actor actor = localization_data.actor;
|
||||||
|
|
|
@ -69,7 +69,7 @@ namespace traffic_manager {
|
||||||
/// Controller object.
|
/// Controller object.
|
||||||
PIDController controller;
|
PIDController controller;
|
||||||
/// Number of vehicles registered with the traffic manager.
|
/// Number of vehicles registered with the traffic manager.
|
||||||
uint number_of_vehicles;
|
uint64_t number_of_vehicles;
|
||||||
/// Reference to Carla's debug helper object.
|
/// Reference to Carla's debug helper object.
|
||||||
cc::DebugHelper &debug_helper;
|
cc::DebugHelper &debug_helper;
|
||||||
|
|
||||||
|
|
|
@ -13,7 +13,7 @@
|
||||||
namespace traffic_manager {
|
namespace traffic_manager {
|
||||||
|
|
||||||
namespace chr = std::chrono;
|
namespace chr = std::chrono;
|
||||||
using TimeInstance = chr::time_point<chr::_V2::system_clock, chr::nanoseconds>;
|
using TimeInstance = chr::time_point<chr::system_clock, chr::nanoseconds>;
|
||||||
|
|
||||||
/// Structure to hold the actuation signals.
|
/// Structure to hold the actuation signals.
|
||||||
struct ActuationSignal {
|
struct ActuationSignal {
|
||||||
|
|
|
@ -21,11 +21,11 @@ namespace traffic_manager {
|
||||||
/// Stage name.
|
/// Stage name.
|
||||||
std::string stage_name;
|
std::string stage_name;
|
||||||
/// Throughput clock.
|
/// Throughput clock.
|
||||||
chr::time_point<chr::_V2::system_clock, chr::nanoseconds> throughput_clock;
|
chr::time_point<chr::system_clock, chr::nanoseconds> throughput_clock;
|
||||||
/// Throughput counter.
|
/// Throughput counter.
|
||||||
uint throughput_counter;
|
uint64_t throughput_counter;
|
||||||
/// Inter-update clock.
|
/// Inter-update clock.
|
||||||
chr::time_point<chr::_V2::system_clock, chr::nanoseconds> inter_update_clock;
|
chr::time_point<chr::system_clock, chr::nanoseconds> inter_update_clock;
|
||||||
/// Inter-update duration.
|
/// Inter-update duration.
|
||||||
chr::duration<float> inter_update_duration;
|
chr::duration<float> inter_update_duration;
|
||||||
|
|
||||||
|
|
|
@ -45,7 +45,7 @@ namespace traffic_manager {
|
||||||
return waypoint->GetTransform().rotation.GetForwardVector();
|
return waypoint->GetTransform().rotation.GetForwardVector();
|
||||||
}
|
}
|
||||||
|
|
||||||
uint SimpleWaypoint::SetNextWaypoint(const std::vector<SimpleWaypointPtr> &waypoints) {
|
uint64_t SimpleWaypoint::SetNextWaypoint(const std::vector<SimpleWaypointPtr> &waypoints) {
|
||||||
for (auto &simple_waypoint: waypoints) {
|
for (auto &simple_waypoint: waypoints) {
|
||||||
next_waypoints.push_back(simple_waypoint);
|
next_waypoints.push_back(simple_waypoint);
|
||||||
}
|
}
|
||||||
|
|
|
@ -59,7 +59,7 @@ namespace traffic_manager {
|
||||||
uint64_t GetId() const;
|
uint64_t GetId() const;
|
||||||
|
|
||||||
/// This method is used to set the next waypoints.
|
/// This method is used to set the next waypoints.
|
||||||
uint SetNextWaypoint(const std::vector<SimpleWaypointPtr> &next_waypoints);
|
uint64_t SetNextWaypoint(const std::vector<SimpleWaypointPtr> &next_waypoints);
|
||||||
|
|
||||||
/// This method is used to set the closest left waypoint for a lane change.
|
/// This method is used to set the closest left waypoint for a lane change.
|
||||||
void SetLeftWaypoint(SimpleWaypointPtr waypoint);
|
void SetLeftWaypoint(SimpleWaypointPtr waypoint);
|
||||||
|
|
|
@ -10,7 +10,7 @@
|
||||||
|
|
||||||
namespace traffic_manager {
|
namespace traffic_manager {
|
||||||
|
|
||||||
static const uint NO_SIGNAL_PASSTHROUGH_INTERVAL = 5u;
|
static const uint64_t NO_SIGNAL_PASSTHROUGH_INTERVAL = 5u;
|
||||||
|
|
||||||
TrafficLightStage::TrafficLightStage(
|
TrafficLightStage::TrafficLightStage(
|
||||||
std::string stage_name,
|
std::string stage_name,
|
||||||
|
@ -45,7 +45,7 @@ namespace traffic_manager {
|
||||||
// Selecting the output frame based on the selection key.
|
// Selecting the output frame based on the selection key.
|
||||||
const auto current_planner_frame = frame_selector ? planner_frame_a : planner_frame_b;
|
const auto current_planner_frame = frame_selector ? planner_frame_a : planner_frame_b;
|
||||||
// Looping over registered actors.
|
// Looping over registered actors.
|
||||||
for (uint i = 0u; i < number_of_vehicles; ++i) {
|
for (uint64_t i = 0u; i < number_of_vehicles; ++i) {
|
||||||
|
|
||||||
bool traffic_light_hazard = false;
|
bool traffic_light_hazard = false;
|
||||||
const LocalizationToTrafficLightData &data = localization_frame->at(i);
|
const LocalizationToTrafficLightData &data = localization_frame->at(i);
|
||||||
|
|
|
@ -35,7 +35,7 @@ namespace traffic_manager {
|
||||||
using SimpleWaypointPtr = std::shared_ptr<SimpleWaypoint>;
|
using SimpleWaypointPtr = std::shared_ptr<SimpleWaypoint>;
|
||||||
using TrafficLight = carla::SharedPtr<cc::TrafficLight>;
|
using TrafficLight = carla::SharedPtr<cc::TrafficLight>;
|
||||||
using TLS = carla::rpc::TrafficLightState;
|
using TLS = carla::rpc::TrafficLightState;
|
||||||
using TimeInstance = chr::time_point<chr::_V2::system_clock, chr::nanoseconds>;
|
using TimeInstance = chr::time_point<chr::system_clock, chr::nanoseconds>;
|
||||||
|
|
||||||
/// This class provides the information about the Traffic Lights at the
|
/// This class provides the information about the Traffic Lights at the
|
||||||
/// junctions.
|
/// junctions.
|
||||||
|
@ -69,7 +69,7 @@ namespace traffic_manager {
|
||||||
/// No signal negotiation mutex.
|
/// No signal negotiation mutex.
|
||||||
std::mutex no_signal_negotiation_mutex;
|
std::mutex no_signal_negotiation_mutex;
|
||||||
/// Number of vehicles registered with the traffic manager.
|
/// Number of vehicles registered with the traffic manager.
|
||||||
uint number_of_vehicles;
|
uint64_t number_of_vehicles;
|
||||||
|
|
||||||
|
|
||||||
void DrawLight(TLS traffic_light_state, const Actor &ego_actor) const;
|
void DrawLight(TLS traffic_light_state, const Actor &ego_actor) const;
|
||||||
|
|
|
@ -223,7 +223,7 @@ namespace traffic_manager {
|
||||||
if (!(std::find(list_of_ids.begin(), list_of_ids.end(), tl->GetId()) != list_of_ids.end())) {
|
if (!(std::find(list_of_ids.begin(), list_of_ids.end(), tl->GetId()) != list_of_ids.end())) {
|
||||||
const TLGroup tl_group = boost::static_pointer_cast<cc::TrafficLight>(tl)->GetGroupTrafficLights();
|
const TLGroup tl_group = boost::static_pointer_cast<cc::TrafficLight>(tl)->GetGroupTrafficLights();
|
||||||
list_of_all_groups.push_back(tl_group);
|
list_of_all_groups.push_back(tl_group);
|
||||||
for (uint i=0u; i<tl_group.size(); i++) {
|
for (uint64_t i=0u; i<tl_group.size(); i++) {
|
||||||
list_of_ids.push_back(tl_group.at(i).get()->GetId());
|
list_of_ids.push_back(tl_group.at(i).get()->GetId());
|
||||||
if(i!=0u) {
|
if(i!=0u) {
|
||||||
tl_to_freeze.push_back(tl_group.at(i));
|
tl_to_freeze.push_back(tl_group.at(i));
|
||||||
|
|
Loading…
Reference in New Issue