Fixed compiler check failures
This commit is contained in:
parent
e02ee7daad
commit
33678a173f
|
@ -43,7 +43,7 @@ namespace traffic_manager {
|
|||
if (data_frame != nullptr &&
|
||||
number_of_vehicles != (*data_frame.get()).size()) {
|
||||
|
||||
number_of_vehicles = (*data_frame.get()).size();
|
||||
number_of_vehicles = static_cast<uint>((*data_frame.get()).size());
|
||||
// Allocating array for command batching.
|
||||
commands = std::make_shared<std::vector<cr::Command>>(number_of_vehicles);
|
||||
}
|
||||
|
|
|
@ -6,8 +6,6 @@ namespace traffic_manager {
|
|||
world_map = _world_map;
|
||||
}
|
||||
|
||||
CarlaDataAccessLayer::~CarlaDataAccessLayer() {}
|
||||
|
||||
using WaypointPtr = carla::SharedPtr<cc::Waypoint>;
|
||||
std::vector<std::pair<WaypointPtr, WaypointPtr>> CarlaDataAccessLayer::GetTopology() const {
|
||||
return world_map->GetTopology();
|
||||
|
|
|
@ -22,8 +22,6 @@ namespace traffic_manager {
|
|||
|
||||
CarlaDataAccessLayer(carla::SharedPtr<cc::Map> world_map);
|
||||
|
||||
~CarlaDataAccessLayer();
|
||||
|
||||
/// This method retrieves a list of topology segments from the simulator.
|
||||
using WaypointPtr = carla::SharedPtr<cc::Waypoint>;
|
||||
std::vector<std::pair<WaypointPtr, WaypointPtr>> GetTopology() const;
|
||||
|
|
|
@ -85,8 +85,8 @@ namespace CollisionStageConstants {
|
|||
bool collision_hazard = false;
|
||||
|
||||
// Check every actor in the vicinity if it poses a collision hazard.
|
||||
for (auto i = actor_id_list.begin(); (i != actor_id_list.end()) && !collision_hazard; ++i) {
|
||||
ActorId actor_id = *i;
|
||||
for (auto j = actor_id_list.begin(); (j != actor_id_list.end()) && !collision_hazard; ++j) {
|
||||
ActorId actor_id = *j;
|
||||
try {
|
||||
|
||||
if (actor_id != ego_actor_id) {
|
||||
|
@ -135,7 +135,7 @@ namespace CollisionStageConstants {
|
|||
// Allocating new containers for the changed number of registered vehicles.
|
||||
if (number_of_vehicles != (*localization_frame.get()).size()) {
|
||||
|
||||
number_of_vehicles = (*localization_frame.get()).size();
|
||||
number_of_vehicles = static_cast<uint>((*localization_frame.get()).size());
|
||||
// Allocating output arrays to be shared with motion planner stage.
|
||||
planner_frame_a = std::make_shared<CollisionToPlannerFrame>(number_of_vehicles);
|
||||
planner_frame_b = std::make_shared<CollisionToPlannerFrame>(number_of_vehicles);
|
||||
|
@ -170,8 +170,8 @@ namespace CollisionStageConstants {
|
|||
Polygon reference_polygon = GetPolygon(GetBoundary(reference_vehicle));
|
||||
Polygon other_polygon = GetPolygon(GetBoundary(other_vehicle));
|
||||
|
||||
float reference_vehicle_to_other_geodesic = bg::distance(reference_polygon, other_geodesic_polygon);
|
||||
float other_vehicle_to_reference_geodesic = bg::distance(other_polygon, reference_geodesic_polygon);
|
||||
double reference_vehicle_to_other_geodesic = bg::distance(reference_polygon, other_geodesic_polygon);
|
||||
double other_vehicle_to_reference_geodesic = bg::distance(other_polygon, reference_geodesic_polygon);
|
||||
|
||||
// Whichever vehicle's path is farthest away from the other vehicle gets priority to move.
|
||||
if (geodesic_overlap &&
|
||||
|
@ -196,8 +196,8 @@ namespace CollisionStageConstants {
|
|||
std::deque<Polygon> output;
|
||||
bg::intersection(reference_polygon, other_polygon, output);
|
||||
|
||||
for (uint i = 0u; i < output.size() && !overlap; ++i) {
|
||||
Polygon &p = output.at(i);
|
||||
for (uint j = 0u; j < output.size() && !overlap; ++j) {
|
||||
Polygon &p = output.at(j);
|
||||
if (bg::area(p) > ZERO_AREA) {
|
||||
overlap = true;
|
||||
}
|
||||
|
@ -246,10 +246,10 @@ namespace CollisionStageConstants {
|
|||
auto vehicle_reference = boost::static_pointer_cast<cc::Vehicle>(actor);
|
||||
// At non-signalized junctions, we extend the boundary across the junction and
|
||||
// in all other situations, boundary length is velocity-dependent.
|
||||
for (uint i = 0u;
|
||||
for (uint j = 0u;
|
||||
(boundary_start->DistanceSquared(boundary_end) < std::pow(bbox_extension, 2)) &&
|
||||
(i < waypoint_buffer->size());
|
||||
++i) {
|
||||
(j < waypoint_buffer->size());
|
||||
++j) {
|
||||
|
||||
cg::Vector3D heading_vector = boundary_end->GetForwardVector();
|
||||
cg::Location location = boundary_end->GetLocation();
|
||||
|
@ -259,7 +259,7 @@ namespace CollisionStageConstants {
|
|||
cg::Vector3D scaled_perpendicular = perpendicular_vector * width;
|
||||
left_boundary.push_back(location + cg::Location(scaled_perpendicular));
|
||||
right_boundary.push_back(location + cg::Location(-1 * scaled_perpendicular));
|
||||
boundary_end = waypoint_buffer->at(i);
|
||||
boundary_end = waypoint_buffer->at(j);
|
||||
}
|
||||
|
||||
// Connecting the geodesic path boundary with the vehicle bounding box.
|
||||
|
|
|
@ -44,10 +44,6 @@ namespace bg = boost::geometry;
|
|||
|
||||
private:
|
||||
|
||||
/// Reference to Carla's world object.
|
||||
cc::World &world;
|
||||
/// Reference to Carla's debug helper object.
|
||||
cc::DebugHelper &debug_helper;
|
||||
/// Variables to remember messenger states.
|
||||
int localization_messenger_state;
|
||||
int planner_messenger_state;
|
||||
|
@ -61,6 +57,10 @@ namespace bg = boost::geometry;
|
|||
/// Pointers to messenger objects.
|
||||
std::shared_ptr<LocalizationToCollisionMessenger> localization_messenger;
|
||||
std::shared_ptr<CollisionToPlannerMessenger> planner_messenger;
|
||||
/// Reference to Carla's world object.
|
||||
cc::World &world;
|
||||
/// Reference to Carla's debug helper object.
|
||||
cc::DebugHelper &debug_helper;
|
||||
/// An object used for grid binning vehicles for faster proximity detection.
|
||||
VicinityGrid vicinity_grid;
|
||||
/// The map used to connect actor ids to the array index of data frames.
|
||||
|
|
|
@ -120,8 +120,7 @@ namespace LocalizationConstants {
|
|||
current_road_ids,
|
||||
current_buffer_list,
|
||||
vehicle_id_to_index,
|
||||
actor_list,
|
||||
debug_helper);
|
||||
actor_list);
|
||||
|
||||
if (change_over_point != nullptr) {
|
||||
waypoint_buffer.clear();
|
||||
|
@ -133,13 +132,11 @@ namespace LocalizationConstants {
|
|||
while (waypoint_buffer.back()->DistanceSquared(waypoint_buffer.front())
|
||||
<= std::pow(horizon_size, 2)) {
|
||||
|
||||
uint pre_selection_id = waypoint_buffer.back()->GetWaypoint()->GetId();
|
||||
std::vector<SimpleWaypointPtr> next_waypoints = waypoint_buffer.back()->GetNextWaypoint();
|
||||
|
||||
uint selection_index = 0u;
|
||||
// Pseudo-randomized path selection if found more than one choice.
|
||||
if (next_waypoints.size() > 1) {
|
||||
selection_index = rand() % next_waypoints.size();
|
||||
selection_index = static_cast<uint>(rand()) % next_waypoints.size();
|
||||
}
|
||||
|
||||
waypoint_buffer.push_back(next_waypoints.at(selection_index));
|
||||
|
@ -149,12 +146,12 @@ namespace LocalizationConstants {
|
|||
float target_point_distance = std::max(std::ceil(vehicle_velocity * TARGET_WAYPOINT_TIME_HORIZON),
|
||||
TARGET_WAYPOINT_HORIZON_LENGTH);
|
||||
SimpleWaypointPtr target_waypoint = waypoint_buffer.front();
|
||||
for (uint i = 0u;
|
||||
(i < waypoint_buffer.size()) &&
|
||||
for (uint j = 0u;
|
||||
(j < waypoint_buffer.size()) &&
|
||||
(waypoint_buffer.front()->DistanceSquared(target_waypoint)
|
||||
< std::pow(target_point_distance, 2));
|
||||
++i) {
|
||||
target_waypoint = waypoint_buffer.at(i);
|
||||
++j) {
|
||||
target_waypoint = waypoint_buffer.at(j);
|
||||
}
|
||||
cg::Location target_location = target_waypoint->GetLocation();
|
||||
float dot_product = DeviationDotProduct(vehicle, target_location);
|
||||
|
@ -173,20 +170,20 @@ namespace LocalizationConstants {
|
|||
|
||||
SimpleWaypointPtr look_ahead_point = waypoint_buffer.front();
|
||||
uint look_ahead_index = 0u;
|
||||
for (uint i = 0u;
|
||||
for (uint j = 0u;
|
||||
(waypoint_buffer.front()->DistanceSquared(look_ahead_point)
|
||||
< std::pow(look_ahead_distance, 2)) &&
|
||||
(i < waypoint_buffer.size());
|
||||
++i) {
|
||||
look_ahead_point = waypoint_buffer.at(i);
|
||||
look_ahead_index = i;
|
||||
(j < waypoint_buffer.size());
|
||||
++j) {
|
||||
look_ahead_point = waypoint_buffer.at(j);
|
||||
look_ahead_index = j;
|
||||
}
|
||||
|
||||
bool approaching_junction = false;
|
||||
if (look_ahead_point->CheckJunction() && !(waypoint_buffer.front()->CheckJunction())) {
|
||||
if (speed_limit > HIGHWAY_SPEED) {
|
||||
for (uint i = 0u; (i < look_ahead_index) && !approaching_junction; ++i) {
|
||||
SimpleWaypointPtr swp = waypoint_buffer.at(i);
|
||||
for (uint j = 0u; (j < look_ahead_index) && !approaching_junction; ++j) {
|
||||
SimpleWaypointPtr swp = waypoint_buffer.at(j);
|
||||
if (swp->GetNextWaypoint().size() > 1) {
|
||||
approaching_junction = true;
|
||||
}
|
||||
|
@ -235,7 +232,7 @@ namespace LocalizationConstants {
|
|||
// Allocating new containers for the changed number of registered vehicles.
|
||||
if (number_of_vehicles != actor_list.size()) {
|
||||
|
||||
number_of_vehicles = actor_list.size();
|
||||
number_of_vehicles = static_cast<uint>(actor_list.size());
|
||||
// Allocating the buffer lists.
|
||||
buffer_list_a = std::make_shared<BufferList>(number_of_vehicles);
|
||||
buffer_list_b = std::make_shared<BufferList>(number_of_vehicles);
|
||||
|
@ -295,7 +292,7 @@ namespace LocalizationConstants {
|
|||
|
||||
void LocalizationStage::DrawBuffer(Buffer &buffer) {
|
||||
|
||||
for (int i = 0; i < buffer.size() && i < 5; ++i) {
|
||||
for (uint i = 0u; i < buffer.size() && i < 5; ++i) {
|
||||
debug_helper.DrawPoint(buffer.at(i)->GetLocation(), 0.1f, {255u, 0u, 0u}, 0.5f);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -36,8 +36,6 @@ namespace cc = carla::client;
|
|||
|
||||
private:
|
||||
|
||||
/// Reference to Carla's debug helper object.
|
||||
cc::DebugHelper &debug_helper;
|
||||
/// Variables to remember messenger states.
|
||||
int planner_messenger_state;
|
||||
int collision_messenger_state;
|
||||
|
@ -70,6 +68,8 @@ namespace cc = carla::client;
|
|||
int registered_actors_state;
|
||||
/// Reference to local map-cache object.
|
||||
InMemoryMap &local_map;
|
||||
/// Reference to Carla's debug helper object.
|
||||
cc::DebugHelper &debug_helper;
|
||||
/// Structures to hold waypoint buffers for all vehicles.
|
||||
/// These are shared with the collisions stage.
|
||||
std::shared_ptr<BufferList> buffer_list_a;
|
||||
|
|
|
@ -5,10 +5,10 @@
|
|||
#include <condition_variable>
|
||||
#include <mutex>
|
||||
|
||||
using namespace std::chrono_literals;
|
||||
|
||||
namespace traffic_manager {
|
||||
|
||||
using namespace std::chrono_literals;
|
||||
|
||||
template <typename Data>
|
||||
struct DataPacket {
|
||||
int id;
|
||||
|
|
|
@ -5,8 +5,6 @@ namespace traffic_manager {
|
|||
namespace PlannerConstants {
|
||||
static const float HIGHWAY_SPEED = 50 / 3.6f;
|
||||
static const float INTERSECTION_APPROACH_SPEED = 15 / 3.6f;
|
||||
static const float URBAN_DEFAULT_VELOCITY = 25 / 3.6f;
|
||||
static const float HIGHWAY_DEFAULT_VELOCITY = 50 / 3.6f;
|
||||
static const std::vector<float> URBAN_LONGITUDINAL_DEFAULTS = {0.1f, 0.15f, 0.01f};
|
||||
static const std::vector<float> HIGHWAY_LONGITUDINAL_DEFAULTS = {5.0f, 0.0f, 0.1f};
|
||||
static const std::vector<float> LATERAL_DEFAULTS = {10.0f, 0.0f, 0.1f};
|
||||
|
@ -18,22 +16,20 @@ namespace PlannerConstants {
|
|||
std::shared_ptr<CollisionToPlannerMessenger> collision_messenger,
|
||||
std::shared_ptr<TrafficLightToPlannerMessenger> traffic_light_messenger,
|
||||
std::shared_ptr<PlannerToControlMessenger> control_messenger,
|
||||
cc::DebugHelper &debug_helper,
|
||||
float urban_target_velocity = URBAN_DEFAULT_VELOCITY,
|
||||
float highway_target_velocity = HIGHWAY_DEFAULT_VELOCITY,
|
||||
float urban_target_velocity = 25 / 3.6f,
|
||||
float highway_target_velocity = 50 / 3.6f,
|
||||
std::vector<float> longitudinal_parameters = URBAN_LONGITUDINAL_DEFAULTS,
|
||||
std::vector<float> highway_longitudinal_parameters = HIGHWAY_LONGITUDINAL_DEFAULTS,
|
||||
std::vector<float> lateral_parameters = LATERAL_DEFAULTS)
|
||||
: urban_target_velocity(urban_target_velocity),
|
||||
: localization_messenger(localization_messenger),
|
||||
collision_messenger(collision_messenger),
|
||||
traffic_light_messenger(traffic_light_messenger),
|
||||
control_messenger(control_messenger),
|
||||
urban_target_velocity(urban_target_velocity),
|
||||
highway_target_velocity(highway_target_velocity),
|
||||
longitudinal_parameters(longitudinal_parameters),
|
||||
highway_longitudinal_parameters(highway_longitudinal_parameters),
|
||||
lateral_parameters(lateral_parameters),
|
||||
localization_messenger(localization_messenger),
|
||||
control_messenger(control_messenger),
|
||||
collision_messenger(collision_messenger),
|
||||
traffic_light_messenger(traffic_light_messenger),
|
||||
debug_helper(debug_helper) {
|
||||
lateral_parameters(lateral_parameters) {
|
||||
|
||||
// Initializing the output frame selector.
|
||||
frame_selector = true;
|
||||
|
@ -158,7 +154,7 @@ namespace PlannerConstants {
|
|||
if (localization_frame != nullptr &&
|
||||
number_of_vehicles != (*localization_frame.get()).size()) {
|
||||
|
||||
number_of_vehicles = (*localization_frame.get()).size();
|
||||
number_of_vehicles = static_cast<uint>((*localization_frame.get()).size());
|
||||
// Allocate output frames.
|
||||
control_frame_a = std::make_shared<PlannerToControlFrame>(number_of_vehicles);
|
||||
control_frame_b = std::make_shared<PlannerToControlFrame>(number_of_vehicles);
|
||||
|
|
|
@ -27,7 +27,6 @@ namespace cc = carla::client;
|
|||
|
||||
private:
|
||||
|
||||
cc::DebugHelper &debug_helper;
|
||||
/// Selection key to switch between the output frames.
|
||||
bool frame_selector;
|
||||
/// Variables to remember messenger states.
|
||||
|
@ -44,19 +43,19 @@ namespace cc = carla::client;
|
|||
std::shared_ptr<TrafficLightToPlannerFrame> traffic_light_frame;
|
||||
/// Pointers to messenger objects connecting to various stages.
|
||||
std::shared_ptr<LocalizationToPlannerMessenger> localization_messenger;
|
||||
std::shared_ptr<PlannerToControlMessenger> control_messenger;
|
||||
std::shared_ptr<CollisionToPlannerMessenger> collision_messenger;
|
||||
std::shared_ptr<TrafficLightToPlannerMessenger> traffic_light_messenger;
|
||||
std::shared_ptr<PlannerToControlMessenger> control_messenger;
|
||||
/// Map to store states for integral and differential components
|
||||
/// of the PID controller for every vehicle
|
||||
std::unordered_map<ActorId, StateEntry> pid_state_map;
|
||||
/// Target velocities.
|
||||
float urban_target_velocity;
|
||||
float highway_target_velocity;
|
||||
/// Configuration parameters for the PID controller.
|
||||
std::vector<float> longitudinal_parameters;
|
||||
std::vector<float> highway_longitudinal_parameters;
|
||||
std::vector<float> lateral_parameters;
|
||||
/// Target velocities.
|
||||
float urban_target_velocity;
|
||||
float highway_target_velocity;
|
||||
/// Controller object.
|
||||
PIDController controller;
|
||||
/// Number of vehicles registered with the traffic manager.
|
||||
|
@ -69,7 +68,6 @@ namespace cc = carla::client;
|
|||
std::shared_ptr<CollisionToPlannerMessenger> collision_messenger,
|
||||
std::shared_ptr<TrafficLightToPlannerMessenger> traffic_light_messenger,
|
||||
std::shared_ptr<PlannerToControlMessenger> control_messenger,
|
||||
cc::DebugHelper &debug_helper,
|
||||
float urban_target_velocity,
|
||||
float highway_target_velocity,
|
||||
std::vector<float> longitudinal_parameters,
|
||||
|
|
|
@ -27,8 +27,8 @@ namespace PIDControllerConstants {
|
|||
};
|
||||
|
||||
// Calculating dt for 'D' and 'I' controller components.
|
||||
chr::duration<double> duration = current_state.time_instance - previous_state.time_instance;
|
||||
double dt = duration.count();
|
||||
chr::duration<float> duration = current_state.time_instance - previous_state.time_instance;
|
||||
float dt = duration.count();
|
||||
|
||||
// Calculating integrals.
|
||||
current_state.deviation_integral = angular_deviation * dt + previous_state.deviation_integral;
|
||||
|
@ -44,8 +44,8 @@ namespace PIDControllerConstants {
|
|||
const std::vector<float> &lateral_parameters) const {
|
||||
|
||||
// Calculating dt for updating the integral component.
|
||||
chr::duration<double> duration = present_state.time_instance - previous_state.time_instance;
|
||||
double dt = duration.count();
|
||||
chr::duration<float> duration = present_state.time_instance - previous_state.time_instance;
|
||||
float dt = duration.count();
|
||||
|
||||
// Longitudinal PID calculation.
|
||||
float expr_v = longitudinal_parameters[0] * present_state.velocity +
|
||||
|
|
|
@ -12,7 +12,6 @@ namespace traffic_manager {
|
|||
: longitudinal_PID_parameters(longitudinal_PID_parameters),
|
||||
longitudinal_highway_PID_parameters(longitudinal_highway_PID_parameters),
|
||||
lateral_PID_parameters(lateral_PID_parameters),
|
||||
urban_target_velocity(urban_target_velocity),
|
||||
client_connection(client_connection),
|
||||
world(client_connection.GetWorld()),
|
||||
debug_helper(client_connection.GetWorld().MakeDebugHelper()) {
|
||||
|
@ -44,15 +43,13 @@ namespace traffic_manager {
|
|||
world, debug_helper);
|
||||
|
||||
traffic_light_stage = std::make_unique<TrafficLightStage>(
|
||||
localization_traffic_light_messenger, traffic_light_planner_messenger,
|
||||
debug_helper);
|
||||
localization_traffic_light_messenger, traffic_light_planner_messenger);
|
||||
|
||||
planner_stage = std::make_unique<MotionPlannerStage>(
|
||||
localization_planner_messenger,
|
||||
collision_planner_messenger,
|
||||
traffic_light_planner_messenger,
|
||||
planner_control_messenger,
|
||||
debug_helper,
|
||||
urban_target_velocity,
|
||||
highway_target_velocity,
|
||||
longitudinal_PID_parameters,
|
||||
|
|
|
@ -39,19 +39,16 @@ namespace cc = carla::client;
|
|||
std::vector<float> longitudinal_PID_parameters;
|
||||
std::vector<float> longitudinal_highway_PID_parameters;
|
||||
std::vector<float> lateral_PID_parameters;
|
||||
/// Target velocities.
|
||||
float highway_target_velocity;
|
||||
float urban_target_velocity;
|
||||
/// Set of all actors registered with traffic manager.
|
||||
AtomicActorSet registered_actors;
|
||||
/// Pointer to local map cache.
|
||||
std::shared_ptr<InMemoryMap> local_map;
|
||||
/// Carla's debug helper object.
|
||||
cc::DebugHelper debug_helper;
|
||||
/// Carla's client connection object.
|
||||
cc::Client client_connection;
|
||||
/// Carla's world object.
|
||||
cc::World world;
|
||||
/// Carla's debug helper object.
|
||||
cc::DebugHelper debug_helper;
|
||||
/// Pointers to messenger objects connecting stage pairs.
|
||||
std::shared_ptr<CollisionToPlannerMessenger> collision_planner_messenger;
|
||||
std::shared_ptr<LocalizationToCollisionMessenger> localization_collision_messenger;
|
||||
|
|
|
@ -1,4 +1,5 @@
|
|||
#include <atomic>
|
||||
#include <chrono>
|
||||
#include <cstdlib>
|
||||
#include <ctime>
|
||||
#include <execinfo.h>
|
||||
|
@ -50,7 +51,7 @@ void handler() {
|
|||
std::vector<Actor> spawn_traffic(
|
||||
cc::Client &client,
|
||||
cc::World &world,
|
||||
uint target_amount = 0) {
|
||||
ulong target_amount = 0u) {
|
||||
|
||||
std::vector<Actor> actor_list;
|
||||
carla::SharedPtr<cc::Map> world_map = world.GetMap();
|
||||
|
@ -100,7 +101,7 @@ std::vector<Actor> spawn_traffic(
|
|||
for (uint i = 0u; i < number_of_vehicles; ++i) {
|
||||
|
||||
cg::Transform spawn_point = spawn_points.at(i);
|
||||
uint blueprint_size = safe_blueprint_library.size();
|
||||
size_t blueprint_size = safe_blueprint_library.size();
|
||||
cc::ActorBlueprint blueprint = safe_blueprint_library.at(i % blueprint_size);
|
||||
|
||||
blueprint.SetAttribute("role_name", "traffic_manager");
|
||||
|
@ -113,7 +114,7 @@ std::vector<Actor> spawn_traffic(
|
|||
// We need to wait till the simulator spawns all vehicles,
|
||||
// tried to use World::WaitForTick but it also wasn't sufficient.
|
||||
// We need to find a better way to do this.
|
||||
std::this_thread::sleep_for(500ms);
|
||||
std::this_thread::sleep_for(std::chrono::milliseconds(500));
|
||||
|
||||
// Gathering actors spawned by the traffic manager.
|
||||
carla::SharedPtr<cc::ActorList> world_actors = world.GetActors();
|
||||
|
@ -122,12 +123,11 @@ std::vector<Actor> spawn_traffic(
|
|||
auto world_vehicle = boost::static_pointer_cast<cc::Vehicle>(world_actor);
|
||||
std::vector<cc::ActorAttributeValue> actor_attributes = world_vehicle->GetAttributes();
|
||||
bool found_traffic_manager_vehicle = false;
|
||||
for (
|
||||
iter = actor_attributes.begin();
|
||||
(iter != actor_attributes.end()) && !found_traffic_manager_vehicle;
|
||||
++iter
|
||||
) {
|
||||
cc::ActorAttributeValue attribute = *iter;
|
||||
for (auto attribute_iter = actor_attributes.begin();
|
||||
(attribute_iter != actor_attributes.end()) && !found_traffic_manager_vehicle;
|
||||
++attribute_iter
|
||||
) {
|
||||
cc::ActorAttributeValue attribute = *attribute_iter;
|
||||
if (attribute.GetValue() == "traffic_manager") {
|
||||
found_traffic_manager_vehicle = true;
|
||||
}
|
||||
|
@ -151,8 +151,7 @@ void destroy_traffic(std::vector<Actor> &actor_list, cc::Client &client) {
|
|||
}
|
||||
|
||||
|
||||
void run_pipeline(cc::World &world, cc::Client &client_conn,
|
||||
uint target_traffic_amount, uint randomization_seed) {
|
||||
void run_pipeline(cc::World &world, cc::Client &client_conn, ulong target_traffic_amount) {
|
||||
|
||||
struct sigaction sa;
|
||||
memset(&sa, 0, sizeof(sa));
|
||||
|
@ -164,7 +163,7 @@ void run_pipeline(cc::World &world, cc::Client &client_conn,
|
|||
client_conn, world, target_traffic_amount);
|
||||
global_actor_list = ®istered_actors;
|
||||
|
||||
client_conn.SetTimeout(2s);
|
||||
client_conn.SetTimeout(std::chrono::seconds(2));
|
||||
|
||||
traffic_manager::Pipeline pipeline(
|
||||
{0.1f, 0.15f, 0.01f},
|
||||
|
@ -216,10 +215,10 @@ int main(int argc, char *argv[]) {
|
|||
std::cout << "[-s] \t\t System randomization seed integer\n";
|
||||
} else {
|
||||
|
||||
uint target_traffic_amount = 0u;
|
||||
ulong target_traffic_amount = 0u;
|
||||
if (argc >= 3 && std::string(argv[1]) == "-n") {
|
||||
try {
|
||||
target_traffic_amount = std::stoi(argv[2]);
|
||||
target_traffic_amount = std::stoul(argv[2]);
|
||||
} catch (const std::exception &e) {
|
||||
carla::log_warning("Failed to parse argument, choosing defaults\n");
|
||||
}
|
||||
|
@ -235,12 +234,12 @@ int main(int argc, char *argv[]) {
|
|||
}
|
||||
|
||||
if (randomization_seed < 0) {
|
||||
std::srand(std::time(0));
|
||||
std::srand(static_cast<uint>(std::time(0)));
|
||||
} else {
|
||||
std::srand(randomization_seed);
|
||||
std::srand(static_cast<uint>(abs(randomization_seed)));
|
||||
}
|
||||
|
||||
run_pipeline(world, client_conn, target_traffic_amount, randomization_seed);
|
||||
run_pipeline(world, client_conn, target_traffic_amount);
|
||||
}
|
||||
|
||||
return 0;
|
||||
|
|
|
@ -14,10 +14,10 @@
|
|||
|
||||
#include "Messenger.h"
|
||||
|
||||
using namespace std::chrono_literals;
|
||||
|
||||
namespace traffic_manager {
|
||||
|
||||
using namespace std::chrono_literals;
|
||||
|
||||
/// This class provides base functionality and template for
|
||||
/// various stages of the pipeline.
|
||||
class PipelineStage {
|
||||
|
|
|
@ -39,7 +39,7 @@ namespace traffic_manager {
|
|||
for (auto &simple_waypoint: waypoints) {
|
||||
next_waypoints.push_back(simple_waypoint);
|
||||
}
|
||||
return waypoints.size();
|
||||
return static_cast<uint>(waypoints.size());
|
||||
}
|
||||
|
||||
void SimpleWaypoint::SetLeftWaypoint(SimpleWaypointPtr _waypoint) {
|
||||
|
|
|
@ -86,8 +86,7 @@ namespace TrafficDistributorConstants {
|
|||
GeoIds current_road_ids,
|
||||
std::shared_ptr<BufferList> buffer_list,
|
||||
std::unordered_map<ActorId, uint> &vehicle_id_to_index,
|
||||
std::vector<carla::SharedPtr<cc::Actor>> &actor_list,
|
||||
cc::DebugHelper &debug_helper) {
|
||||
std::vector<carla::SharedPtr<cc::Actor>> &actor_list) {
|
||||
|
||||
ActorId actor_id = vehicle->GetId();
|
||||
cg::Location vehicle_location = vehicle->GetLocation();
|
||||
|
|
|
@ -104,9 +104,7 @@ namespace cg = carla::geom;
|
|||
GeoIds current_road_ids,
|
||||
std::shared_ptr<BufferList> buffer_list,
|
||||
std::unordered_map<ActorId, uint> &vehicle_id_to_index,
|
||||
std::vector<Actor> &actor_list,
|
||||
cc::DebugHelper &debug_helper);
|
||||
|
||||
std::vector<Actor> &actor_list);
|
||||
};
|
||||
|
||||
}
|
||||
|
|
|
@ -4,13 +4,10 @@ namespace traffic_manager {
|
|||
|
||||
static const uint NO_SIGNAL_PASSTHROUGH_INTERVAL = 5u;
|
||||
|
||||
TrafficLightStage::TrafficLightStage(
|
||||
std::shared_ptr<LocalizationToTrafficLightMessenger> localization_messenger,
|
||||
std::shared_ptr<TrafficLightToPlannerMessenger> planner_messenger,
|
||||
cc::DebugHelper &debug_helper)
|
||||
TrafficLightStage::TrafficLightStage(std::shared_ptr<LocalizationToTrafficLightMessenger> localization_messenger,
|
||||
std::shared_ptr<TrafficLightToPlannerMessenger> planner_messenger)
|
||||
: localization_messenger(localization_messenger),
|
||||
planner_messenger(planner_messenger),
|
||||
debug_helper(debug_helper){
|
||||
planner_messenger(planner_messenger) {
|
||||
|
||||
// Initializing output frame selector.
|
||||
frame_selector = true;
|
||||
|
@ -139,7 +136,7 @@ namespace traffic_manager {
|
|||
if (localization_frame != nullptr &&
|
||||
number_of_vehicles != (*localization_frame.get()).size()) {
|
||||
|
||||
number_of_vehicles = (*localization_frame.get()).size();
|
||||
number_of_vehicles = static_cast<uint>((*localization_frame.get()).size());
|
||||
// Allocating output frames.
|
||||
planner_frame_a = std::make_shared<TrafficLightToPlannerFrame>(number_of_vehicles);
|
||||
planner_frame_b = std::make_shared<TrafficLightToPlannerFrame>(number_of_vehicles);
|
||||
|
|
|
@ -33,7 +33,6 @@ namespace cg = carla::geom;
|
|||
|
||||
private:
|
||||
|
||||
cc::DebugHelper &debug_helper;
|
||||
/// Variables to remember messenger states.
|
||||
int localization_messenger_state;
|
||||
int planner_messenger_state;
|
||||
|
@ -60,10 +59,8 @@ namespace cg = carla::geom;
|
|||
|
||||
public:
|
||||
|
||||
TrafficLightStage(
|
||||
std::shared_ptr<LocalizationToTrafficLightMessenger> localization_messenger,
|
||||
std::shared_ptr<TrafficLightToPlannerMessenger> planner_messenger,
|
||||
cc::DebugHelper &debug_helper);
|
||||
TrafficLightStage(std::shared_ptr<LocalizationToTrafficLightMessenger> localization_messenger,
|
||||
std::shared_ptr<TrafficLightToPlannerMessenger> planner_messenger);
|
||||
~TrafficLightStage();
|
||||
|
||||
void DataReceiver() override;
|
||||
|
|
|
@ -64,8 +64,8 @@ namespace traffic_manager {
|
|||
|
||||
std::string grid_key = MakeKey({grid_ids.first + i, grid_ids.second + j});
|
||||
if (grid_to_actor_id.find(grid_key) != grid_to_actor_id.end()) {
|
||||
for (auto actor: grid_to_actor_id.at(grid_key)) {
|
||||
actors.insert(actor);
|
||||
for (auto grid_actor: grid_to_actor_id.at(grid_key)) {
|
||||
actors.insert(grid_actor);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue