Skip to content

Commit

Permalink
ci(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Jun 21, 2022
1 parent 1394620 commit feb4db1
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -174,7 +174,6 @@ BehaviorModuleOutput LaneChangeModule::plan()

CandidateOutput LaneChangeModule::planCandidate() const
{

// Get lane change lanes
const auto current_lanes = getCurrentLanes();
const auto lane_change_lanes = getLaneChangeLanes(current_lanes, lane_change_lane_length_);
Expand Down Expand Up @@ -395,7 +394,6 @@ std::pair<bool, bool> LaneChangeModule::getSafePath(
// object_debug_ = object_debug;
setObjectDebugVisualization();


return std::make_pair(true, found_safe_path);
}

Expand Down Expand Up @@ -464,8 +462,8 @@ bool LaneChangeModule::isAbortConditionSatisfied() const
std::unordered_map<std::string, LaneChangeObjectDebug> debug_data;
is_path_safe = lane_change_utils::isLaneChangePathSafe(
path.path, current_lanes, check_lanes, objects, current_pose, current_twist,
common_parameters.vehicle_width, common_parameters.vehicle_length, parameters_, debug_data, false,
status_.lane_change_path.acceleration);
common_parameters.vehicle_width, common_parameters.vehicle_length, parameters_, debug_data,
false, status_.lane_change_path.acceleration);
}

// check vehicle velocity thresh
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,9 +13,9 @@
// limitations under the License.

#include "behavior_path_planner/scene_module/lane_change/util.hpp"
#include "behavior_path_planner/scene_module/avoidance/avoidance_utils.hpp"

#include "behavior_path_planner/path_shifter/path_shifter.hpp"
#include "behavior_path_planner/scene_module/avoidance/avoidance_utils.hpp"

#include <lanelet2_extension/utility/query.hpp>
#include <lanelet2_extension/utility/utilities.hpp>
Expand Down Expand Up @@ -448,7 +448,7 @@ bool isLaneChangePathSafe(

if (boost::geometry::overlaps(ego_polygon, obj_polygon)) {
appendDebugInfo(debug_datum, "OverlapInCurrent", false);
return false;
return false;
}

const auto & object_twist = obj.kinematics.initial_twist_with_covariance.twist;
Expand Down Expand Up @@ -482,7 +482,7 @@ bool isLaneChangePathSafe(

if (is_object_in_target) {
for (const auto & obj_path : predicted_paths) {
std::vector<Pose> lerp_ego_pose {};
std::vector<Pose> lerp_ego_pose{};
for (double t = target_lane_check_start_time; t < target_lane_check_end_time;
t += time_resolution) {
Pose expected_obj_pose;
Expand All @@ -502,7 +502,6 @@ bool isLaneChangePathSafe(
continue;
}


lerp_ego_pose.push_back(expected_ego_pose);
if (boost::geometry::overlaps(ego_polygon, obj_polygon)) {
debug_datum.second.lerped_path = lerp_ego_pose;
Expand Down

0 comments on commit feb4db1

Please sign in to comment.