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 Mar 30, 2022
1 parent 6967e2d commit 3458c6f
Show file tree
Hide file tree
Showing 2 changed files with 16 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,8 @@ AnalyticalJerkConstrainedSmoother::AnalyticalJerkConstrainedSmoother(rclcpp::Nod
{
smoother_param_.resample.ds_resample = node.declare_parameter("resample.ds_resample", 0.1);
smoother_param_.resample.num_resample = node.declare_parameter("resample.num_resample", 1.0);
smoother_param_.resample.delta_yaw_threshold = node.declare_parameter("resample.delta_yaw_threshold", 0.785);
smoother_param_.resample.delta_yaw_threshold =
node.declare_parameter("resample.delta_yaw_threshold", 0.785);
smoother_param_.latacc.enable_constant_velocity_while_turning =
node.declare_parameter("latacc.enable_constant_velocity_while_turning", false);
smoother_param_.latacc.constant_velocity_dist_threshold =
Expand All @@ -83,9 +84,11 @@ AnalyticalJerkConstrainedSmoother::AnalyticalJerkConstrainedSmoother(rclcpp::Nod
smoother_param_.forward.min_jerk = node.declare_parameter("forward.min_jerk", -0.3);
smoother_param_.forward.kp = node.declare_parameter("forward.kp", 0.3);
smoother_param_.backward.start_jerk = node.declare_parameter("backward.start_jerk", -0.1);
smoother_param_.backward.min_jerk_mild_stop = node.declare_parameter("backward.min_jerk_mild_stop", -0.3);
smoother_param_.backward.min_jerk_mild_stop =
node.declare_parameter("backward.min_jerk_mild_stop", -0.3);
smoother_param_.backward.min_jerk = node.declare_parameter("backward.min_jerk", -1.5);
smoother_param_.backward.min_acc_mild_stop = node.declare_parameter("backward.min_acc_mild_stop", -1.0);
smoother_param_.backward.min_acc_mild_stop =
node.declare_parameter("backward.min_acc_mild_stop", -1.0);
smoother_param_.backward.min_acc = node.declare_parameter("backward.min_acc", -2.5);
smoother_param_.backward.span_jerk = node.declare_parameter("backward.span_jerk", -0.01);
}
Expand Down
15 changes: 10 additions & 5 deletions planning/motion_velocity_smoother/src/smoother/smoother_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,8 @@

namespace motion_velocity_smoother
{
SmootherBase::SmootherBase(rclcpp::Node & node) {
SmootherBase::SmootherBase(rclcpp::Node & node)
{
std::cout << "SmootherBase constructor!" << std::endl;
base_param_.max_accel = node.declare_parameter("normal.max_acc", 2.0);
std::cout << "max_accel: " << base_param_.max_accel << std::endl;
Expand All @@ -32,11 +33,15 @@ SmootherBase::SmootherBase(rclcpp::Node & node) {
base_param_.max_jerk = node.declare_parameter("normal.max_jerk", 0.3);
base_param_.min_jerk = node.declare_parameter("normal.min_jerk", -0.1);
base_param_.max_lateral_accel = node.declare_parameter("max_lateral_accel", 0.2);
base_param_.decel_distance_before_curve = node.declare_parameter("decel_distance_before_curve", 3.5);
base_param_.decel_distance_after_curve = node.declare_parameter("decel_distance_after_curve", 0.0);
base_param_.decel_distance_before_curve =
node.declare_parameter("decel_distance_before_curve", 3.5);
base_param_.decel_distance_after_curve =
node.declare_parameter("decel_distance_after_curve", 0.0);
base_param_.min_curve_velocity = node.declare_parameter("min_curve_velocity", 1.38);
base_param_.resample_param.max_trajectory_length = node.declare_parameter("max_trajectory_length", 200.0);
base_param_.resample_param.min_trajectory_length = node.declare_parameter("min_trajectory_length", 30.0);
base_param_.resample_param.max_trajectory_length =
node.declare_parameter("max_trajectory_length", 200.0);
base_param_.resample_param.min_trajectory_length =
node.declare_parameter("min_trajectory_length", 30.0);
base_param_.resample_param.resample_time = node.declare_parameter("resample_time", 10.0);
base_param_.resample_param.dense_resample_dt = node.declare_parameter("dense_resample_dt", 0.1);
base_param_.resample_param.dense_min_interval_distance =
Expand Down

0 comments on commit 3458c6f

Please sign in to comment.