提交 191f3b72 编写于 作者: D Dong Li 提交者: GitHub

Merge pull request #14 from jinghaomiao/jinghao_dev

Added lint support for prediction module.
load("//tools:cpplint.bzl", "cpplint")
package(default_visibility = ["//visibility:public"])
cc_library(
......@@ -28,3 +30,5 @@ cc_binary(
"//external:gflags",
],
)
cpplint()
load("//tools:cpplint.bzl", "cpplint")
package(default_visibility = ["//visibility:public"])
cc_library(
......@@ -9,3 +11,5 @@ cc_library(
"//modules/prediction/proto:prediction_proto",
],
)
cpplint()
......@@ -19,7 +19,8 @@
// System gflags
DEFINE_string(prediction_module_name, "prediction",
"Default prediciton module name");
DEFINE_string(prediction_conf_file, "modules/prediction/conf/prediction_conf.pb.txt",
DEFINE_string(prediction_conf_file,
"modules/prediction/conf/prediction_conf.pb.txt",
"Default conf file for prediction");
// Features
......@@ -32,4 +33,4 @@ DEFINE_double(p_var, 0.1, "Error covariance");
DEFINE_double(go_approach_rate, 0.995,
"The rate to approach to the reference line of going straight");
DEFINE_double(cutin_approach_rate, 0.9,
"The rate to approach to the reference line of lane change");
\ No newline at end of file
"The rate to approach to the reference line of lane change");
load("//tools:cpplint.bzl", "cpplint")
package(default_visibility = ["//visibility:public"])
cc_library(
......@@ -18,4 +20,6 @@ cc_library(
deps = [
"@com_github_google_protobuf//:protobuf"
]
)
\ No newline at end of file
)
cpplint()
\ No newline at end of file
......@@ -50,7 +50,7 @@ class Container {
virtual void Insert(const ::google::protobuf::Message& message) = 0;
};
} // namespace prediction
} // namespace apollo
} // namespace prediction
} // namespace apollo
#endif // MODULES_PREDICTION_CONTAINER_CONTAINER_H_
#endif // MODULES_PREDICTION_CONTAINER_CONTAINER_H_
......@@ -56,5 +56,5 @@ void ContainerManager::RegisterContainer(const std::string& name) {
containers_[name] = CreateContainer(name);
}
}
}
} // namespace prediction
} // namespace apollo
......@@ -24,6 +24,7 @@
#include <unordered_map>
#include <string>
#include <memory>
#include "modules/prediction/container/container.h"
#include "modules/common/macro.h"
......@@ -65,7 +66,7 @@ class ContainerManager {
DECLARE_SINGLETON(ContainerManager)
};
} // namespace prediction
} // namespace apollo
} // namespace prediction
} // namespace apollo
#endif // MODULES_PREDICTION_CONTAINER_CONTAINER_MANAGER_H_
#endif // MODULES_PREDICTION_CONTAINER_CONTAINER_MANAGER_H_
load("//tools:cpplint.bzl", "cpplint")
package(default_visibility = ["//visibility:public"])
cc_library(
......@@ -23,3 +25,5 @@ cc_library(
"//modules/prediction/common:prediction_common",
],
)
cpplint()
......@@ -19,6 +19,7 @@
#include <iomanip>
#include <cmath>
#include <unordered_set>
#include <utility>
#include "modules/common/log.h"
#include "modules/common/math/math_utils.h"
......@@ -42,7 +43,7 @@ double Damp(const double x, const double sigma) {
} // namespace
Obstacle::Obstacle() :
Obstacle::Obstacle() :
id_(-1),
type_(PerceptionObstacle::UNKNOWN_MOVABLE),
feature_history_(0),
......@@ -88,14 +89,14 @@ Feature* Obstacle::mutable_feature(size_t i) {
const Feature& Obstacle::latest_feature() {
std::lock_guard<std::mutex> lock(mutex_);
CHECK(feature_history_.size() > 0);
CHECK_GT(feature_history_.size(), 0);
return feature_history_.front();
}
Feature* Obstacle::mutable_latest_feature() {
std::lock_guard<std::mutex> lock(mutex_);
CHECK(feature_history_.size() > 0);
CHECK_GT(feature_history_.size(), 0);
return &(feature_history_.front());
}
......@@ -381,8 +382,8 @@ void Obstacle::InitKFMotionTracker(Feature* feature) {
kf_motion_tracker_enabled_ = true;
}
void Obstacle::UpdateKFMotionTracker(Feature* feature) {
double delta_ts = 0.0;
void Obstacle::UpdateKFMotionTracker(Feature* feature) {
double delta_ts = 0.0;
if (feature_history_.size() > 0) {
delta_ts = feature->timestamp() - feature_history_.front().timestamp();
}
......
......@@ -39,7 +39,7 @@ namespace prediction {
class Obstacle {
public:
explicit Obstacle();
Obstacle();
virtual ~Obstacle();
......@@ -138,4 +138,4 @@ class Obstacle {
} // namespace prediction
} // namespace apollo
#endif // MODULES_PREDICTION_CONTAINER_OBSTACLES_OBSTACLE_H_
#endif // MODULES_PREDICTION_CONTAINER_OBSTACLES_OBSTACLE_H_
......@@ -32,7 +32,7 @@ class ObstaclesContainer : public Container {
/**
* @brief Constructor
*/
explicit ObstaclesContainer() = default;
ObstaclesContainer() = default;
/**
* @brief Destructor
......@@ -43,10 +43,10 @@ class ObstaclesContainer : public Container {
* @brief Insert a data message into the container
* @param Data message to be inserted in protobuf
*/
virtual void Insert(const ::google::protobuf::Message& message) override;
void Insert(const ::google::protobuf::Message& message) override;
};
} // namespace prediction
} // namespace apollo
} // namespace prediction
} // namespace apollo
#endif // MODULES_PREDICTION_CONTAINER_OBSTACLES_OBSTACLES_H_
#endif // MODULES_PREDICTION_CONTAINER_OBSTACLES_OBSTACLES_H_
load("//tools:cpplint.bzl", "cpplint")
package(default_visibility = ["//visibility:public"])
cc_library(
......@@ -7,4 +9,6 @@ cc_library(
deps = [
"//modules/prediction/container:container",
]
)
\ No newline at end of file
)
cpplint()
\ No newline at end of file
......@@ -32,7 +32,7 @@ class PoseContainer : public Container {
/**
* @brief Constructor
*/
explicit PoseContainer() = default;
PoseContainer() = default;
/**
* @brief Destructor
......@@ -43,10 +43,10 @@ class PoseContainer : public Container {
* @brief Insert a data message into the container
* @param Data message to be inserted in protobuf
*/
virtual void Insert(const ::google::protobuf::Message& message) override;
void Insert(const ::google::protobuf::Message& message) override;
};
} // namespace prediction
} // namespace apollo
} // namespace prediction
} // namespace apollo
#endif // MODULES_PREDICTION_CONTAINER_POSE_OBSTACLES_H_
#endif // MODULES_PREDICTION_CONTAINER_POSE_OBSTACLES_H_
load("//tools:cpplint.bzl", "cpplint")
package(default_visibility = ["//visibility:public"])
cc_library(
......@@ -31,4 +33,6 @@ cc_library(
deps = [
]
)
\ No newline at end of file
)
cpplint()
\ No newline at end of file
......@@ -44,7 +44,8 @@ class Evaluator {
virtual ~Evaluator() = default;
};
} // namespace prediction
} // namespace apollo
} // namespace prediction
} // namespace apollo
#endif // MODULES_PREDICTION_EVALUATOR_EVALUATOR_H_
#endif // MODULES_PREDICTION_EVALUATOR_EVALUATOR_H_
......@@ -39,5 +39,5 @@ std::unique_ptr<Evaluator> EvaluatorFactory::CreateEvaluator(
return evaluator;
}
}
}
\ No newline at end of file
} // namespace prediction
} // namespace apollo
......@@ -57,7 +57,7 @@ class EvaluatorFactory
DECLARE_SINGLETON(EvaluatorFactory);
};
} // namespace prediction
} // namespace apollo
} // namespace prediction
} // namespace apollo
#endif // MODULES_PREDICTION_EVALUATOR_EVALUATOR_FACTORY_H_
\ No newline at end of file
#endif // MODULES_PREDICTION_EVALUATOR_EVALUATOR_FACTORY_H_
......@@ -28,5 +28,5 @@ const Evaluator* EvaluatorManager::GetEvaluator() {
void EvaluatorManager::Run(
const ::apollo::perception::PerceptionObstacles& perception_obstacles) {}
}
}
} // namespace prediction
} // namespace apollo
......@@ -48,12 +48,13 @@ class EvaluatorManager {
*/
const Evaluator* GetEvaluator();
void Run(const ::apollo::perception::PerceptionObstacles& perception_obstacles);
void Run(
const ::apollo::perception::PerceptionObstacles& perception_obstacles);
DECLARE_SINGLETON(EvaluatorManager)
};
} // namespace prediction
} // namespace apollo
} // namespace prediction
} // namespace apollo
#endif // MODULES_PREDICTION_EVALUATOR_EVALUATOR_MANAGER_H_
#endif // MODULES_PREDICTION_EVALUATOR_EVALUATOR_MANAGER_H_
......@@ -16,13 +16,13 @@
#include "modules/prediction/prediction.h"
#include "modules/prediction/proto/prediction_obstacle.pb.h"
#include "modules/common/adapters/adapter_manager.h"
#include "modules/prediction/container/container_manager.h"
#include "modules/prediction/evaluator/evaluator_manager.h"
#include "modules/prediction/predictor/predictor_manager.h"
#include "modules/prediction/common/prediction_gflags.h"
#include "modules/prediction/proto/prediction_obstacle.pb.h"
#include "modules/common/util/file.h"
namespace apollo {
......@@ -81,7 +81,6 @@ void Prediction::OnPerception(const PerceptionObstacles &perception_obstacles) {
}
ContainerManager::instance()
->mutable_container("Obstacles")->Insert(perception_obstacles);
ContainerManager::instance()->mutable_container("Obstacles")->Insert(perception_obstacles);
EvaluatorManager::instance()->Run(perception_obstacles);
PredictorManager::instance()->Run(perception_obstacles);
// AdapterManager::PublishPrediction(PredictorManager::instance()->GetPredictions());
......
......@@ -21,6 +21,8 @@
#ifndef MODULES_PREDICTION_PREDICTION_H_
#define MODULES_PREDICTION_PREDICTION_H_
#include <string>
#include "ros/include/ros/ros.h"
#include "modules/perception/proto/perception_obstacle.pb.h"
#include "modules/prediction/proto/prediction_conf.pb.h"
......@@ -38,30 +40,30 @@ class Prediction : public apollo::common::ApolloApp {
/**
* @brief Destructor
*/
virtual ~Prediction() = default;
~Prediction() = default;
/**
* @brief Get name of the node
* @return Name of the node
*/
virtual std::string Name() const override;
std::string Name() const override;
/**
* @brief Initialize the node
* @return Status of the initialization
*/
virtual ::apollo::common::Status Init() override;
::apollo::common::Status Init() override;
/**
* @brief Start the node
* @return Status of the starting process
*/
virtual ::apollo::common::Status Start() override;
::apollo::common::Status Start() override;
/**
* @brief Stop the node
*/
virtual void Stop() override;
void Stop() override;
private:
::apollo::common::Status OnError(const std::string& error_msg);
......
load("//tools:cpplint.bzl", "cpplint")
package(default_visibility = ["//visibility:public"])
cc_library(
......@@ -31,4 +33,6 @@ cc_library(
deps = [
]
)
\ No newline at end of file
)
cpplint()
\ No newline at end of file
......@@ -44,7 +44,7 @@ class Predictor {
virtual ~Predictor() = default;
};
} // namespace prediction
} // namespace apollo
} // namespace prediction
} // namespace apollo
#endif // MODULES_PREDICTION_PREDICTOR_PREDICTOR_H_
#endif // MODULES_PREDICTION_PREDICTOR_PREDICTOR_H_
......@@ -39,5 +39,5 @@ std::unique_ptr<Predictor> PredictorFactory::CreatePredictor(
return predictor;
}
}
}
\ No newline at end of file
} // namespace prediction
} // namespace apollo
......@@ -57,7 +57,7 @@ class PredictorFactory
DECLARE_SINGLETON(PredictorFactory);
};
} // namespace prediction
} // namespace apollo
} // namespace prediction
} // namespace apollo
#endif // MODULES_PREDICTION_PREDICTOR_PREDICTOR_FACTORY_H_
\ No newline at end of file
#endif // MODULES_PREDICTION_PREDICTOR_PREDICTOR_FACTORY_H_
......@@ -28,5 +28,6 @@ const Predictor* PredictorManager::GetPredictor() {
void PredictorManager::Run(
const ::apollo::perception::PerceptionObstacles& perception_obstacles) {}
}
}
} // namespace prediction
} // namespace apollo
......@@ -48,12 +48,14 @@ class PredictorManager {
*/
const Predictor* GetPredictor();
void Run(const ::apollo::perception::PerceptionObstacles& perception_obstacles);
void Run(
const ::apollo::perception::PerceptionObstacles& perception_obstacles);
DECLARE_SINGLETON(PredictorManager)
};
} // namespace prediction
} // namespace apollo
} // namespace prediction
} // namespace apollo
#endif // MODULES_PREDICTION_PREDICTOR_PREDICTOR_MANAGER_H_
#endif // MODULES_PREDICTION_PREDICTOR_PREDICTOR_MANAGER_H_
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册