Skip to content

Commit

Permalink
select the optimal trajectory where no collision occurs with other ve…
Browse files Browse the repository at this point in the history
…hicles
  • Loading branch information
hayoung-kim committed Dec 1, 2017
1 parent 9d20b32 commit c4d0c4e
Show file tree
Hide file tree
Showing 4 changed files with 55 additions and 6 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ add_definitions(-std=c++11)
set(CXX_FLAGS "-Wall")
set(CMAKE_CXX_FLAGS, "${CXX_FLAGS}")

set(sources src/main.cpp src/polysolver.cpp src/coordinate_transforms.cpp)
set(sources src/main.cpp src/polysolver.cpp src/coordinate_transforms.cpp src/checkcollision.cpp)


if(${CMAKE_SYSTEM_NAME} MATCHES "Darwin")
Expand Down
12 changes: 12 additions & 0 deletions src/checkcollision.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,16 @@

#include <math.h>
#include <iostream>
#include <vector>

#include "Eigen-3.3/Eigen/Core"
#include "Eigen-3.3/Eigen/QR"
#include "Eigen-3.3/Eigen/Dense"

using namespace std;
using namespace Eigen;
#include "checkcollision.h"

int contains(double n, vector<double> range) {
float a = range[0], b = range[1];
if (b<a) {a=b; b=range[0];}
Expand Down
10 changes: 10 additions & 0 deletions src/checkcollision.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
#ifndef _CHECKCOLLISION_H_
#define _CHECKCOLLISION_H_

int contains(double n, vector<double> range);

int overlap(vector<double> a, vector<double> b);

int checkCollision(double s0, double d0, double theta0, double s1, double d1, double theta1);

#endif
37 changes: 32 additions & 5 deletions src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@ using json = nlohmann::json;
#include "spline.h"
#include "polysolver.h"
#include "coordinate_transforms.h"
#include "checkcollision.h"

typedef struct Vehicle {
int id;
Expand All @@ -30,6 +31,7 @@ typedef struct Vehicle {
double s;
double d;
double speed;
// vector<double> future_s;
} Vehicle;

// Checks if the SocketIO event has JSON data.
Expand Down Expand Up @@ -311,7 +313,7 @@ int main() {
int n_subset = n_use_previous_path;
if (n_subset >= prev_path_size) {n_subset = prev_path_size;}

cout << "n_subset: " << n_subset << endl;
// cout << "n_subset: " << n_subset << endl;

for (int h=0; h<n_subset; h++){
next_x_vals.push_back(previous_path_x[h]);
Expand Down Expand Up @@ -354,13 +356,38 @@ int main() {
_ = lateralTrajectories(d0, d0dot, d0ddot, 6.0, d_trajectories, d_costs);
_ = lateralTrajectories(d0, d0dot, d0ddot, 10.0, d_trajectories, d_costs);

// SELECT PATH

// OPTIMAL PATH SELECTION WITH COLLISION CHECK
int MAX_ITER_FIND_OPT = 40;
for (int i=0; i<MAX_ITER_FIND_OPT; i++) {
bool is_crash = false;
vector<int> opt_idx = optimalCombination(s_costs, d_costs);
optimal_s_coeff = s_trajectories.col(opt_idx[0]);
optimal_d_coeff = d_trajectories.col(opt_idx[1]);

// check collision for hrz
for (int t=0; t< n_planning_horizon; t++) {
// my position
double _s = getPosition(optimal_s_coeff, i*0.02);
double _d = getPosition(optimal_d_coeff, i*0.02);

// other car's predicted position
for (int n=0; n < NearbyVehicles.size(); n++) {
Vehicle other_car = NearbyVehicles[n];
double _s_other = other_car.s + t * 0.02 * other_car.speed;
double _d_other = other_car.d;
int crash = checkCollision(_s, _d, 0.0, _s_other, _d_other, 0.0);
if (crash == 1) {is_crash = true; break;}
}
if (is_crash) {break;}
}
if (is_crash) {s_costs(opt_idx[0]) = 99999; d_costs(opt_idx[1])=99999;}
}


vector<int> opt_idx = optimalCombination(s_costs, d_costs);
optimal_s_coeff = s_trajectories.col(opt_idx[0]);
optimal_d_coeff = d_trajectories.col(opt_idx[1]);
// vector<int> opt_idx = optimalCombination(s_costs, d_costs);
// optimal_s_coeff = s_trajectories.col(opt_idx[0]);
// optimal_d_coeff = d_trajectories.col(opt_idx[1]);

// RUN!!

Expand Down

0 comments on commit c4d0c4e

Please sign in to comment.