Skip to content

Commit

Permalink
Merge branch 'main' into fix/image_projection_based_fusion/fix_bug
Browse files Browse the repository at this point in the history
  • Loading branch information
kminoda authored Feb 14, 2024
2 parents a9392c9 + 7d8ee41 commit fa07107
Show file tree
Hide file tree
Showing 7 changed files with 14 additions and 2 deletions.
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
/**:
ros__parameters:
# constraints param for normal driving
max_vel: 11.1 # max velocity limit [m/s]

normal:
min_acc: -0.5 # min deceleration [m/ss]
max_acc: 1.0 # max acceleration [m/ss]
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
/**:
ros__parameters:
# constraints param for normal driving
max_vel: 11.1 # max velocity limit [m/s]

normal:
min_acc: -0.5 # min deceleration [m/ss]
max_acc: 1.0 # max acceleration [m/ss]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -173,7 +173,7 @@ rcl_interfaces::msg::SetParametersResult MotionVelocitySmootherNode::onParameter
update_param_bool("enable_lateral_acc_limit", p.enable_lateral_acc_limit);
update_param_bool("enable_steering_rate_limit", p.enable_steering_rate_limit);

update_param("max_velocity", p.max_velocity);
update_param("max_vel", p.max_velocity);
update_param(
"margin_to_insert_external_velocity_limit", p.margin_to_insert_external_velocity_limit);
update_param("replan_vel_deviation", p.replan_vel_deviation);
Expand Down Expand Up @@ -277,7 +277,7 @@ void MotionVelocitySmootherNode::initCommonParam()
p.enable_lateral_acc_limit = declare_parameter<bool>("enable_lateral_acc_limit");
p.enable_steering_rate_limit = declare_parameter<bool>("enable_steering_rate_limit");

p.max_velocity = declare_parameter<double>("max_velocity"); // 72.0 kmph
p.max_velocity = declare_parameter<double>("max_vel");
p.margin_to_insert_external_velocity_limit =
declare_parameter<double>("margin_to_insert_external_velocity_limit");
p.replan_vel_deviation = declare_parameter<double>("replan_vel_deviation");
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
/**:
ros__parameters:
# constraints param for normal driving
max_vel: 11.1 # max velocity limit [m/s]

normal:
min_acc: -1.0 # min deceleration [m/ss]
max_acc: 1.0 # max acceleration [m/ss]
Expand Down
2 changes: 2 additions & 0 deletions planning/obstacle_stop_planner/config/common.param.yaml
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
/**:
ros__parameters:
# constraints param for normal driving
max_vel: 11.1 # max velocity limit [m/s]

normal:
min_acc: -0.5 # min deceleration [m/ss]
max_acc: 1.0 # max acceleration [m/ss]
Expand Down
2 changes: 2 additions & 0 deletions planning/planning_test_utils/config/test_common.param.yaml
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
/**:
ros__parameters:
# constraints param for normal driving
max_vel: 11.1 # max velocity limit [m/s]

normal:
min_acc: -1.0 # min deceleration [m/ss]
max_acc: 1.0 # max acceleration [m/ss]
Expand Down
2 changes: 2 additions & 0 deletions planning/static_centerline_optimizer/config/common.param.yaml
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
/**:
ros__parameters:
# constraints param for normal driving
max_vel: 11.1 # max velocity limit [m/s]

normal:
min_acc: -0.5 # min deceleration [m/ss]
max_acc: 1.0 # max acceleration [m/ss]
Expand Down

0 comments on commit fa07107

Please sign in to comment.