External Velocity Limit Selector#
Purpose#
The external_velocity_limit_selector_node
is a node that keeps consistency of external velocity limits. This module subscribes
- velocity limit command sent by API,
- velocity limit command sent by Autoware internal modules.
VelocityLimit.msg contains not only max velocity but also information about the acceleration/jerk constraints on deceleration. The external_velocity_limit_selector_node
integrates the lowest velocity limit and the highest jerk constraint to calculate the hardest velocity limit that protects all the deceleration points and max velocities sent by API and Autoware internal modules.
Inner-workings / Algorithms#
WIP
Inputs#
Name | Type | Description |
---|---|---|
~input/velocity_limit_from_api |
autoware_internal_planning_msgs::msg::VelocityLimit | velocity limit from api |
~input/velocity_limit_from_internal |
autoware_internal_planning_msgs::msg::VelocityLimit | velocity limit from autoware internal modules |
~input/velocity_limit_clear_command_from_internal |
autoware_internal_planning_msgs::msg::VelocityLimitClearCommand | velocity limit clear command |
Outputs#
Name | Type | Description |
---|---|---|
~output/max_velocity |
autoware_internal_planning_msgs::msg::VelocityLimit | current information of the hardest velocity limit |
Parameters#
Name | Type | Description | Default | Range |
---|---|---|---|---|
max_velocity | float | Default max velocity [m/s] | 20 | N/A |
Name | Type | Description | Default | Range |
----------------- | -------- | ------------------------------- | ----------- | --------- |
max_vel | float | max velocity limit [m/s] | 11.1 | N/A |
normal.min_acc | float | min deceleration [m/ss] | -0.5 | N/A |
normal.max_acc | float | max acceleration [m/ss] | 1 | N/A |
normal.min_jerk | float | min jerk [m/sss] | -0.5 | N/A |
normal.max_jerk | float | max jerk [m/sss] | 1 | N/A |
limit.min_acc | float | min deceleration limit [m/ss] | -2.5 | N/A |
limit.max_acc | float | max acceleration [m/ss] | 1 | N/A |
limit.min_jerk | float | min jerk [m/sss] | -1.5 | N/A |
limit.max_jerk | float | max jerk [m/sss] | 1.5 | N/A |