Skip to content

Commit 74a463d

Browse files
takayuki5168satoshi-ota
authored andcommitted
feat(motion_velocity_smoother): use common max_vel (autowarefoundation#6388)
Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent 36dc88a commit 74a463d

File tree

7 files changed

+14
-2
lines changed

7 files changed

+14
-2
lines changed

planning/external_velocity_limit_selector/config/default_common.param.yaml

+2
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,8 @@
11
/**:
22
ros__parameters:
33
# constraints param for normal driving
4+
max_vel: 11.1 # max velocity limit [m/s]
5+
46
normal:
57
min_acc: -0.5 # min deceleration [m/ss]
68
max_acc: 1.0 # max acceleration [m/ss]

planning/motion_velocity_smoother/config/default_common.param.yaml

+2
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,8 @@
11
/**:
22
ros__parameters:
33
# constraints param for normal driving
4+
max_vel: 11.1 # max velocity limit [m/s]
5+
46
normal:
57
min_acc: -0.5 # min deceleration [m/ss]
68
max_acc: 1.0 # max acceleration [m/ss]

planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -173,7 +173,7 @@ rcl_interfaces::msg::SetParametersResult MotionVelocitySmootherNode::onParameter
173173
update_param_bool("enable_lateral_acc_limit", p.enable_lateral_acc_limit);
174174
update_param_bool("enable_steering_rate_limit", p.enable_steering_rate_limit);
175175

176-
update_param("max_velocity", p.max_velocity);
176+
update_param("max_vel", p.max_velocity);
177177
update_param(
178178
"margin_to_insert_external_velocity_limit", p.margin_to_insert_external_velocity_limit);
179179
update_param("replan_vel_deviation", p.replan_vel_deviation);
@@ -277,7 +277,7 @@ void MotionVelocitySmootherNode::initCommonParam()
277277
p.enable_lateral_acc_limit = declare_parameter<bool>("enable_lateral_acc_limit");
278278
p.enable_steering_rate_limit = declare_parameter<bool>("enable_steering_rate_limit");
279279

280-
p.max_velocity = declare_parameter<double>("max_velocity"); // 72.0 kmph
280+
p.max_velocity = declare_parameter<double>("max_vel");
281281
p.margin_to_insert_external_velocity_limit =
282282
declare_parameter<double>("margin_to_insert_external_velocity_limit");
283283
p.replan_vel_deviation = declare_parameter<double>("replan_vel_deviation");

planning/obstacle_cruise_planner/config/default_common.param.yaml

+2
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,8 @@
11
/**:
22
ros__parameters:
33
# constraints param for normal driving
4+
max_vel: 11.1 # max velocity limit [m/s]
5+
46
normal:
57
min_acc: -1.0 # min deceleration [m/ss]
68
max_acc: 1.0 # max acceleration [m/ss]

planning/obstacle_stop_planner/config/common.param.yaml

+2
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,8 @@
11
/**:
22
ros__parameters:
33
# constraints param for normal driving
4+
max_vel: 11.1 # max velocity limit [m/s]
5+
46
normal:
57
min_acc: -0.5 # min deceleration [m/ss]
68
max_acc: 1.0 # max acceleration [m/ss]

planning/planning_test_utils/config/test_common.param.yaml

+2
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,8 @@
11
/**:
22
ros__parameters:
33
# constraints param for normal driving
4+
max_vel: 11.1 # max velocity limit [m/s]
5+
46
normal:
57
min_acc: -1.0 # min deceleration [m/ss]
68
max_acc: 1.0 # max acceleration [m/ss]

planning/static_centerline_optimizer/config/common.param.yaml

+2
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,8 @@
11
/**:
22
ros__parameters:
33
# constraints param for normal driving
4+
max_vel: 11.1 # max velocity limit [m/s]
5+
46
normal:
57
min_acc: -0.5 # min deceleration [m/ss]
68
max_acc: 1.0 # max acceleration [m/ss]

0 commit comments

Comments
 (0)