提交 5b86f159 编写于 作者: C Calvin Miao

Added prediction conf in proto

......@@ -65,7 +65,7 @@ double RandomDouble(const double s, const double t, unsigned int rand_seed) {
return s + (t - s) / 16383.0 * (rand_r(&rand_seed) & 16383);
}
int double_compare(const double d1, const double d2, const double epsilon) {
int DoubleCompare(const double d1, const double d2, const double epsilon) {
DCHECK(!std::isnan(d1));
DCHECK(!std::isnan(d2));
......
......@@ -152,7 +152,7 @@ T Clamp(const T value, T bound1, T bound2) {
return value;
}
int double_compare(
int DoubleCompare(
const double d1, const double d2,
const double epsilon = std::numeric_limits<double>::epsilon());
......
......@@ -73,16 +73,16 @@ TEST(MathUtilsTest, Square) {
}
TEST(MathUtilsTest, Double) {
EXPECT_EQ(double_compare(234.32, 93.9), 1);
EXPECT_EQ(double_compare({234.32}, {93.9}), 1);
EXPECT_EQ(double_compare(234.32, 93.9, 1e-5), 1);
EXPECT_EQ(double_compare({234.32}, {93.9}, 1e-5), 1);
EXPECT_EQ(DoubleCompare(234.32, 93.9), 1);
EXPECT_EQ(DoubleCompare({234.32}, {93.9}), 1);
EXPECT_EQ(DoubleCompare(234.32, 93.9, 1e-5), 1);
EXPECT_EQ(DoubleCompare({234.32}, {93.9}, 1e-5), 1);
EXPECT_EQ(double_compare(23.32, 93.9), -1);
EXPECT_EQ(double_compare(4.32, 4.32), 0);
EXPECT_EQ(double_compare(2.1, 2.0009, 1e-5), 1);
EXPECT_EQ(double_compare(1.1, 2.0009, 1e-5), -1);
EXPECT_EQ(double_compare(2.1, 2.0009, 1), 0);
EXPECT_EQ(DoubleCompare(23.32, 93.9), -1);
EXPECT_EQ(DoubleCompare(4.32, 4.32), 0);
EXPECT_EQ(DoubleCompare(2.1, 2.0009, 1e-5), 1);
EXPECT_EQ(DoubleCompare(1.1, 2.0009, 1e-5), -1);
EXPECT_EQ(DoubleCompare(2.1, 2.0009, 1), 0);
}
} // namespace math
......
......@@ -81,8 +81,8 @@ PathPoint TrajectoryAnalyzer::QueryMatchedPathPoint(const double x,
index_min + 1 == trajectory_points_.size() ? index_min : index_min + 1;
if (index_start == index_end ||
common::math::double_compare(trajectory_points_[index_start].s,
trajectory_points_[index_end].s) == 0) {
common::math::DoubleCompare(trajectory_points_[index_start].s,
trajectory_points_[index_end].s) == 0) {
return trajectory_points_[index_start];
}
......
......@@ -21,3 +21,8 @@ DEFINE_string(prediction_module_name, "prediction",
"Default prediciton module name");
DEFINE_string(prediction_conf_file, "modules/prediction/conf/prediction_conf.pb.txt",
"Default conf file for prediction");
// Features
DEFINE_double(double_precision, 1e-6, "precision of double");
DEFINE_double(max_acc, 4.0, "Upper bound of acceleration");
DEFINE_double(min_acc, -4.0, "Lower bound of deceleration");
......@@ -23,4 +23,8 @@
DECLARE_string(prediction_module_name);
DECLARE_string(prediction_conf_file);
DECLARE_double(double_precision);
DECLARE_double(max_acc);
DECLARE_double(min_acc);
#endif // MODULES_PREDICTION_COMMON_PREDICTION_GFLAGS_H_
......@@ -15,10 +15,12 @@ cc_library(
srcs = ["obstacle.cc"],
hdrs = ["obstacle.h"],
deps = [
"//modules/common:log",
"//modules/common/math:kalman_filter",
"//modules/common/proto:error_code_proto",
"//modules/common/math:math_utils",
"//modules/perception/proto:perception_proto",
"//modules/prediction/proto:feature_proto",
"//modules/common:log",
"//modules/common/math:kalman_filter",
"//modules/prediction/common:prediction_common",
],
)
\ No newline at end of file
)
......@@ -20,6 +20,8 @@
#include <cmath>
#include "modules/common/log.h"
#include "modules/common/math/math_utils.h"
#include "modules/prediction/common/prediction_gflags.h"
namespace apollo {
namespace prediction {
......@@ -256,8 +258,7 @@ void Obstacle::SetAcceleration(Feature* feature) {
const Point3D& curr_velocity = feature->velocity();
const Point3D& prev_velocity = feature_history_.front().velocity();
// TODO(kechxu) add a gflag of double precision
if (curr_ts > prev_ts) {
if (apollo::common::math::DoubleCompare(curr_ts, prev_ts) == 1) {
double damping_x = Damp(curr_velocity.x(), 0.001);
double damping_y = Damp(curr_velocity.y(), 0.001);
double damping_z = Damp(curr_velocity.z(), 0.001);
......@@ -265,10 +266,13 @@ void Obstacle::SetAcceleration(Feature* feature) {
acc_x = (curr_velocity.x() - prev_velocity.x()) / (curr_ts - prev_ts);
acc_y = (curr_velocity.y() - prev_velocity.y()) / (curr_ts - prev_ts);
acc_z = (curr_velocity.z() - prev_velocity.z()) / (curr_ts - prev_ts);
// TODO(kechxu) clamp the acc
acc_x *= damping_x;
acc_y *= damping_y;
acc_z *= damping_z;
acc_x = apollo::common::math::Clamp(
acc_x * damping_x, FLAGS_min_acc, FLAGS_max_acc);
acc_y = apollo::common::math::Clamp(
acc_y * damping_y, FLAGS_min_acc, FLAGS_max_acc);
acc_z = apollo::common::math::Clamp(
acc_z * damping_z, FLAGS_min_acc, FLAGS_max_acc);
}
}
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册