Skip to content

feat(autoware_behavior_path_planner): remove max_module_size param #7764

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -9,79 +9,69 @@
enable_simultaneous_execution_as_candidate_module: true
keep_last: false
priority: 6
max_module_size: 1

external_request_lane_change_right:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: true
keep_last: false
priority: 6
max_module_size: 1

lane_change_left:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: true
keep_last: false
priority: 5
max_module_size: 1

lane_change_right:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: true
keep_last: false
priority: 5
max_module_size: 1

start_planner:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: false
keep_last: false
priority: 0
max_module_size: 1

side_shift:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: false
keep_last: false
priority: 2
max_module_size: 1

goal_planner:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: false
keep_last: true
priority: 1
max_module_size: 1

static_obstacle_avoidance:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: false
keep_last: false
priority: 4
max_module_size: 1

avoidance_by_lane_change:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: false
keep_last: false
priority: 3
max_module_size: 1

dynamic_obstacle_avoidance:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: true
keep_last: false
priority: 7
max_module_size: 1

sampling_planner:
enable_module: true
Expand All @@ -90,4 +80,3 @@
enable_simultaneous_execution_as_candidate_module: false
keep_last: true
priority: 16
max_module_size: 1
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,6 @@ struct ModuleConfigParameters
bool enable_simultaneous_execution_as_approved_module{false};
bool enable_simultaneous_execution_as_candidate_module{false};
uint8_t priority{0};
uint8_t max_module_size{0};
};
```

Expand All @@ -101,7 +100,6 @@ Code is [here](https://github.com/autowarefoundation/autoware.universe/blob/b173
| `enable_simultaneous_execution_as_candidate_module` | bool | if true, the manager allows its scene modules to run with other scene modules as **candidate module**. |
| `enable_simultaneous_execution_as_approved_module` | bool | if true, the manager allows its scene modules to run with other scene modules as **approved module**. |
| `priority` | uint8_t | the manager decides execution priority based on this parameter. The smaller the number is, the higher the priority is. |
| `max_module_size` | uint8_t | the sub-manager can run some modules simultaneously. this parameter set the maximum number of the launched modules. |

### Scene modules

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,7 @@ struct SceneModuleStatus
class PlannerManager
{
public:
PlannerManager(rclcpp::Node & node, const size_t max_iteration_num);
explicit PlannerManager(rclcpp::Node & node);

/**
* @brief run all candidate and approved modules.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,8 +70,7 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod

const std::lock_guard<std::mutex> lock(mutex_manager_); // for planner_manager_

const auto & p = planner_data_->parameters;
planner_manager_ = std::make_shared<PlannerManager>(*this, p.max_iteration_num);
planner_manager_ = std::make_shared<PlannerManager>(*this);

for (const auto & name : declare_parameter<std::vector<std::string>>("launch_modules")) {
// workaround: Since ROS 2 can't get empty list, launcher set [''] on the parameter.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@

namespace autoware::behavior_path_planner
{
PlannerManager::PlannerManager(rclcpp::Node & node, const size_t max_iteration_num)
PlannerManager::PlannerManager(rclcpp::Node & node)
: plugin_loader_(
"autoware_behavior_path_planner",
"autoware::behavior_path_planner::SceneModuleManagerInterface"),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -205,7 +205,16 @@ class SceneModuleManagerInterface
});
}

bool canLaunchNewModule() const { return observers_.size() < config_.max_module_size; }
/**
* Determine if a new module can be launched. It ensures that only one instance of a particular
* scene module type is registered at a time.
*
* When this returns true:
* - A new instance of the scene module can be launched.
* - No other instance of the same name of scene module is currently active or registered.
*
*/
bool canLaunchNewModule() const { return observers_.empty(); }

/**
* Determine if the module is always executable, regardless of the state of other modules.
Expand Down Expand Up @@ -290,7 +299,6 @@ class SceneModuleManagerInterface
*node, ns + "enable_simultaneous_execution_as_candidate_module");
config_.keep_last = getOrDeclareParameter<bool>(*node, ns + "keep_last");
config_.priority = getOrDeclareParameter<int>(*node, ns + "priority");
config_.max_module_size = getOrDeclareParameter<int>(*node, ns + "max_module_size");
}

// init rtc configuration
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,6 @@ struct ModuleConfigParameters
bool enable_simultaneous_execution_as_candidate_module{false};
bool keep_last{false};
uint8_t priority{0};
uint8_t max_module_size{0};
};

struct BehaviorPathPlannerParameters
Expand Down
Loading