Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions op_planner/include/op_planner/MappingHelpers.h
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,7 @@ class MappingHelpers {
static WayPoint* GetLastWaypoint(RoadNetwork& map);
static void FindAdjacentLanes(RoadNetwork& map);
static void FindAdjacentLanesV2(RoadNetwork& map, const double& min_d = 1.2, const double& max_d = 3.5);
static bool PointInMap(RoadNetwork& map,const WayPoint& pos);
/**
*
*
Expand Down
2 changes: 2 additions & 0 deletions op_planner/include/op_planner/RoadNetwork.h
Original file line number Diff line number Diff line change
Expand Up @@ -1273,6 +1273,7 @@ class PlanningParams
bool enableTrafficLightBehavior;
bool enableStopSignBehavior;
bool enableTimeOutAvoidance;
bool enableBlockingRolloutsOutOfMap;
double avoidanceTimeOut;

bool enabTrajectoryVelocities;
Expand Down Expand Up @@ -1319,6 +1320,7 @@ class PlanningParams
enableLaneChange = false;
enableStopSignBehavior = false;
enabTrajectoryVelocities = false;
enableBlockingRolloutsOutOfMap = false;
minIndicationDistance = 15;

enableTimeOutAvoidance = false;
Expand Down
4 changes: 4 additions & 0 deletions op_planner/include/op_planner/TrajectoryEvaluator.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
#define TRAJECTORY_EVALUATOR_H_

#include "PlanningHelpers.h"
#include "MappingHelpers.h"
#include "PlannerCommonDef.h"

namespace PlannerHNS
Expand Down Expand Up @@ -67,6 +68,7 @@ class TrajectoryEvaluator
}

public:
RoadNetwork m_Map;
std::vector<WayPoint> all_contour_points_;
std::vector<WayPoint> all_trajectories_points_;
std::vector<WayPoint> collision_points_;
Expand Down Expand Up @@ -99,6 +101,8 @@ class TrajectoryEvaluator

void calculateDistanceCosts(const PlanningParams& params, const double& c_lateral_d, const std::vector<std::vector<WayPoint> >& roll_outs, const std::vector<WayPoint>& contour_points, const std::vector<WayPoint>& trajectory_points, std::vector<TrajectoryCost>& trajectory_costs, std::vector<WayPoint>& collision_points);

void blockTrajectoryOutOfRoad(const std::vector<std::vector<WayPoint> >& roll_outs, std::vector<TrajectoryCost>& trajectory_costs);

TrajectoryCost findBestTrajectory(const PlanningParams& params, const int& prev_curr_index, const bool& b_keep_curr, std::vector<TrajectoryCost> trajectory_costs);

};
Expand Down
2 changes: 1 addition & 1 deletion op_planner/include/op_planner/VectorMapLoader.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ namespace PlannerHNS {

class VectorMapLoader {
public:
VectorMapLoader(int map_version = 1, bool enable_lane_change = false, bool load_curb = false, bool load_lines = false, bool load_wayarea = false);
VectorMapLoader(int map_version = 1, bool enable_lane_change = false, bool load_curb = false, bool load_lines = false, bool load_wayarea = true);
virtual ~VectorMapLoader();

/**
Expand Down
12 changes: 12 additions & 0 deletions op_planner/src/MappingHelpers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -420,6 +420,18 @@ Lane* MappingHelpers::GetClosestLaneFromMap(const WayPoint& pos, RoadNetwork& ma
return pCloseLane;
}

bool MappingHelpers::PointInMap(RoadNetwork& map,const WayPoint& pos)
{
for(unsigned int i=0; i < map.boundaries.size(); i++)
{
if ( PlanningHelpers::PointInsidePolygon(map.boundaries.at(i).points, pos) )
{
return true;
}
}
return false;
}

WayPoint MappingHelpers::GetFirstWaypoint(RoadNetwork& map)
{
for(unsigned int j=0; j< map.roadSegments.size(); j ++)
Expand Down
1 change: 1 addition & 0 deletions op_planner/src/PlanningHelpers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3952,6 +3952,7 @@ void PlanningHelpers::InitializeSafetyPolygon(const PlannerHNS::WayPoint& curr_s
car_border.points.push_back(top_left_car);
}


int PlanningHelpers::PointInsidePolygon(const std::vector<GPSPoint>& points,const GPSPoint& p)
{
int counter = 0;
Expand Down
20 changes: 19 additions & 1 deletion op_planner/src/TrajectoryEvaluator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ TrajectoryCost TrajectoryEvaluator::doOneStep(const std::vector<std::vector<WayP
best_trajectory.lane_index = 0;

if(roll_outs.size() == 0)
{
{
std::cout << " ### Zero generated rollouts, But They should = " << params.rollOutNumber + 1 << std::endl;
return best_trajectory;
}
Expand Down Expand Up @@ -87,6 +87,9 @@ TrajectoryCost TrajectoryEvaluator::doOneStep(const std::vector<std::vector<WayP

collision_points_.clear();
calculateDistanceCosts(params, critical_lateral_distance, local_roll_outs_, all_contour_points_, all_trajectories_points_, trajectory_costs_, collision_points_);
if(params.enableBlockingRolloutsOutOfMap == true){
blockTrajectoryOutOfRoad(local_roll_outs_, trajectory_costs_);
}
// collision_points_.clear();
// collision_points_.insert(collision_points_.begin(), all_contour_points_.begin(), all_contour_points_.end());
// collision_points_.insert(collision_points_.begin(), all_trajectories_points_.begin(), all_trajectories_points_.end());
Expand Down Expand Up @@ -364,6 +367,21 @@ void TrajectoryEvaluator::initializeCosts(const std::vector<std::vector<WayPoint
}
}

void TrajectoryEvaluator::blockTrajectoryOutOfRoad(const std::vector<std::vector<WayPoint> >& roll_outs, std::vector<TrajectoryCost>& trajectory_costs)
{
for(unsigned int i=0; i<roll_outs.size(); i++)
{
for(unsigned int j=0; j<roll_outs.at(i).size(); j++)
{
if( ! MappingHelpers::PointInMap(m_Map,roll_outs.at(i).at(j)) )
{
trajectory_costs.at(i).bBlocked = true;
break;
}
}
}
}

void TrajectoryEvaluator::initializeSafetyPolygon(const WayPoint& curr_state, const CAR_BASIC_INFO& car_info,
const VehicleState& vehicle_state, const double& c_lateral_d,
const double& c_long_front_d, const double& c_long_back_d,
Expand Down