提交 5e4aca92 编写于 作者: Y Yifei Jiang 提交者: Jiaming Tao

[planning] fixed clint complaint. (#872)

上级 1a049caf
......@@ -136,7 +136,7 @@ bool Frame::Init(const PlanningConfig& config) {
<< init_pose_.DebugString();
return false;
}
// TODO add fuctions to help select the best reference_line(s)
// TODO(all) add fuctions to help select the best reference_line(s)
reference_line_ = reference_lines.front();
if (FLAGS_enable_prediction) {
......
......@@ -24,6 +24,7 @@
#include <memory>
#include <queue>
#include <unordered_map>
#include <utility>
namespace apollo {
namespace planning {
......@@ -31,7 +32,8 @@ namespace planning {
template <typename I, typename T>
class IndexedQueue {
public:
IndexedQueue(std::size_t max_queue_size) : max_queue_size_(max_queue_size){};
explicit IndexedQueue(std::size_t max_queue_size) :
max_queue_size_(max_queue_size) {}
const T *Find(const I id) const {
auto iter = map_.find(id);
if (iter == map_.end()) {
......
......@@ -36,7 +36,8 @@ namespace planning {
class PathDecision {
public:
PathDecision(const std::vector<const PathObstacle *> &path_obstacles);
explicit PathDecision(
const std::vector<const PathObstacle *> &path_obstacles);
PathDecision(const std::vector<const Obstacle *> &obstacles,
const ReferenceLine &reference_line);
......
......@@ -18,10 +18,10 @@
* @file
**/
#include "modules/planning/common/path_obstacle.h"
#include <unordered_map>
#include <limits>
#include "modules/planning/common/path_obstacle.h"
#include "modules/common/log.h"
#include "modules/planning/common/planning_gflags.h"
......
......@@ -24,6 +24,7 @@
#include <list>
#include <string>
#include <vector>
#include <unordered_map>
#include "gtest/gtest_prod.h"
......@@ -62,7 +63,7 @@ class PathObstacle {
public:
PathObstacle();
PathObstacle(const planning::Obstacle* obstacle);
explicit PathObstacle(const planning::Obstacle* obstacle);
bool Init(const ReferenceLine* reference_line);
......
......@@ -37,9 +37,10 @@ PathData* PlanningData::mutable_path_data() { return &path_data_; }
SpeedData* PlanningData::mutable_speed_data() { return &speed_data_; }
bool PlanningData::CombinePathAndSpeedProfile(const double time_resolution,
const double relative_time,
DiscretizedTrajectory* ptr_discretized_trajectory) {
bool PlanningData::CombinePathAndSpeedProfile(
const double time_resolution,
const double relative_time,
DiscretizedTrajectory* ptr_discretized_trajectory) {
CHECK(time_resolution > 0.0);
CHECK(ptr_discretized_trajectory != nullptr);
......
......@@ -21,6 +21,7 @@
#ifndef MODULES_PLANNING_COMMON_SPEED_LIMIT_H_
#define MODULES_PLANNING_COMMON_SPEED_LIMIT_H_
#include <utility>
#include <vector>
namespace apollo {
......
......@@ -62,7 +62,8 @@ class DiscretizedTrajectory : public Trajectory {
template <typename Iter>
void PrependTrajectoryPoints(Iter begin, Iter end) {
if (!trajectory_points_.empty() && begin != end) {
CHECK((end - 1)->relative_time() < trajectory_points_.front().relative_time());
CHECK((end - 1)->relative_time()
< trajectory_points_.front().relative_time());
}
trajectory_points_.insert(trajectory_points_.begin(), begin, end);
}
......
......@@ -18,6 +18,8 @@
* @file publishable_trajectory.cpp
**/
#include <utility>
#include "modules/planning/common/trajectory/publishable_trajectory.h"
namespace apollo {
......
......@@ -21,6 +21,7 @@
#ifndef MODULES_PLANNING_COMMON_TRAJECTORY_PUBLISHABLE_TRAJECTORY_H_
#define MODULES_PLANNING_COMMON_TRAJECTORY_PUBLISHABLE_TRAJECTORY_H_
#include <vector>
#include "modules/planning/common/trajectory/discretized_trajectory.h"
#include "modules/planning/proto/planning.pb.h"
......
......@@ -21,6 +21,7 @@
#ifndef MODULES_PLANNING_MATH_HERMITE_SPLINE_H_
#define MODULES_PLANNING_MATH_HERMITE_SPLINE_H_
#include <utility>
#include <array>
#include "modules/common/log.h"
......@@ -28,8 +29,8 @@
namespace apollo {
namespace planning {
//Hermite spline implementation that works for 1d and 2d space interpolation.
//Valid input type T: double, Eigen::Vector2d
// Hermite spline implementation that works for 1d and 2d space interpolation.
// Valid input type T: double, Eigen::Vector2d
template <typename T, std::uint32_t N>
class HermiteSpline {
public:
......
......@@ -24,6 +24,7 @@
#include <cmath>
#include <vector>
#include <algorithm>
#include "modules/common/proto/pnc_point.pb.h"
#include "modules/common/status/status.h"
......
......@@ -21,6 +21,8 @@
#include "modules/planning/optimizer/dp_poly_path/dp_poly_path_optimizer.h"
#include <string>
#include <utility>
#include <vector>
#include "modules/common/util/file.h"
#include "modules/planning/common/planning_gflags.h"
......
......@@ -22,6 +22,9 @@
#define MODULES_PLANNING_OPTIMIZER_DP_POLY_PATH_DP_ROAD_GRAPH_H_
#include <vector>
#include <utility>
#include <limits>
#include <string>
#include "modules/common/proto/pnc_point.pb.h"
......
......@@ -25,7 +25,6 @@
#include "modules/common/adapters/adapter_gflags.h"
#include "modules/common/adapters/adapter_manager.h"
#include "modules/common/configs/vehicle_config_helper.h"
#include "modules/common/configs/vehicle_config_helper.h"
#include "modules/common/log.h"
#include "modules/common/util/file.h"
#include "modules/planning/common/path_decision.h"
......
......@@ -113,7 +113,8 @@ bool QpSplinePathGenerator::Generate(
double dl = spline.Derivative(s);
double ddl = spline.SecondOrderDerivative(s);
ReferencePoint ref_point = reference_line_.get_reference_point(s);
Eigen::Vector2d xy_point = CartesianFrenetConverter::CalculateCartesianPoint(
Eigen::Vector2d xy_point =
CartesianFrenetConverter::CalculateCartesianPoint(
ref_point.heading(), {ref_point.x(), ref_point.y()},
l);
xy_point[0] = xy_point.x() - x_diff;
......
......@@ -22,8 +22,6 @@
#include "modules/planning/common/planning_gflags.h"
#include "modules/planning/common/speed_limit.h"
#include <string>
namespace apollo {
namespace planning {
......@@ -80,6 +78,5 @@ void SpeedOptimizer::RecordSTGraphDebug(
{speed_data.speed_vector().begin(), speed_data.speed_vector().end()});
}
} // namespace planning
} // namespace apollo
......@@ -22,6 +22,7 @@
#define MODULES_PLANNING_OPTIMIZER_SPEED_OPTIMIZER_H_
#include <string>
#include <vector>
#include "modules/planning/optimizer/optimizer.h"
......@@ -50,7 +51,6 @@ class SpeedOptimizer : public Optimizer {
const SpeedLimit& speed_limits, const SpeedData& speed_data);
void RecordDebugInfo(const SpeedData& speed_data);
};
} // namespace planning
......
......@@ -23,9 +23,10 @@
#include <memory>
#include <vector>
#include <limits>
#include <string>
#include "modules/planning/proto/planning.pb.h"
#include "modules/common/math/polygon2d.h"
#include "modules/planning/common/path_obstacle.h"
#include "modules/planning/optimizer/st_graph/st_graph_point.h"
......@@ -55,7 +56,7 @@ class StGraphBoundary : public common::math::Polygon2d {
~StGraphBoundary() = default;
// TODO: add this function.
// TODO(all): add this function.
// bool IsEmpty() const { return points.empty(); }
bool IsPointInBoundary(const StGraphPoint& st_graph_point) const;
bool IsPointInBoundary(const STPoint& st_point) const;
......
......@@ -14,12 +14,11 @@
* limitations under the License.
*****************************************************************************/
#include "modules/planning/common/path_obstacle.h"
#include "modules/planning/optimizer/st_graph/st_graph_data.h"
#include <algorithm>
#include <cmath>
#include "modules/planning/common/path_obstacle.h"
#include "modules/planning/optimizer/st_graph/st_graph_data.h"
#include "gmock/gmock.h"
#include "gtest/gtest.h"
......
......@@ -18,6 +18,8 @@
* @file decider.cpp
**/
#include <limits>
#include "modules/common/configs/vehicle_config_helper.h"
#include "modules/common/log.h"
#include "modules/common/vehicle_state/vehicle_state.h"
......@@ -79,7 +81,7 @@ int Decider::MakeMainStopDecision(Frame* frame,
for (const auto path_obstacle : path_obstacles.Items()) {
const auto& obstacle = path_obstacle->Obstacle();
const auto& object_decision = path_obstacle->LongitudinalDecision();
if (not object_decision.has_stop()) {
if (!object_decision.has_stop()) {
continue;
}
......
......@@ -17,6 +17,7 @@
#include "modules/planning/planner/rtk/rtk_replay_planner.h"
#include <fstream>
#include <utility>
#include "modules/common/log.h"
#include "modules/common/util/string_tokenizer.h"
......
......@@ -24,6 +24,7 @@
#include <string>
#include <utility>
#include <vector>
#include <limits>
#include "boost/math/tools/minima.hpp"
......
......@@ -37,8 +37,8 @@ namespace planning {
class ReferenceLine {
public:
ReferenceLine() = default;
ReferenceLine(const std::vector<ReferencePoint>& reference_points);
ReferenceLine(const hdmap::Path& hdmap_path);
explicit ReferenceLine(const std::vector<ReferencePoint>& reference_points);
explicit ReferenceLine(const hdmap::Path& hdmap_path);
ReferenceLine(const std::vector<ReferencePoint>& reference_points,
const std::vector<hdmap::LaneSegment>& lane_segments,
const double max_approximation_error);
......
......@@ -43,7 +43,7 @@ std::vector<common::TrajectoryPoint> compute_reinit_stitching_trajectory() {
init_point.set_relative_time(0.0);
return std::vector<common::TrajectoryPoint>(1, init_point);
};
}
// Planning from current vehicle state:
// if 1. the auto-driving mode is off or
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册