Skip to content
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

[Planning Pipeline Refactoring] #2 Enable chaining planners #2457

Merged
merged 26 commits into from
Dec 6, 2023
Merged
Show file tree
Hide file tree
Changes from 22 commits
Commits
Show all changes
26 commits
Select commit Hold shift + click to select a range
9bd1d86
Enable using multiple planners in a row
sjahr Oct 16, 2023
01ff6fb
Update configs
sjahr Oct 16, 2023
77cd906
Enable planner chaining
sjahr Oct 17, 2023
c4e5485
Update planner_plugin param to planner_plugins param
sjahr Oct 18, 2023
a7f9006
Make compile
sjahr Nov 16, 2023
c02af96
All planners must have a description!
sjahr Nov 16, 2023
842c980
Fix unittests
sjahr Nov 16, 2023
ef3575f
Fix small bug
sjahr Nov 17, 2023
6130b20
Address compilattion error
sjahr Nov 17, 2023
27f3623
Update migration guide + remove unused variables
sjahr Nov 22, 2023
622db43
Address clang-tidy
sjahr Nov 22, 2023
2775e5b
Satisfy clang-tidy part 2
sjahr Nov 22, 2023
1fc4bfe
Remove unsused param
sjahr Nov 22, 2023
a34e545
Apply suggestions from code review
sjahr Nov 27, 2023
1acfadc
Update planning_plugin to planning_plugins
sjahr Nov 27, 2023
f1aa815
Rename BenchmarkExecutor::plannerConfigurationsExist to pipelinesExist
sjahr Nov 27, 2023
c687de5
Make planner vector a planner map
sjahr Nov 27, 2023
301acac
Re-enable query planner service
sjahr Nov 27, 2023
6259bf6
Add more usefull deprecation warning
sjahr Nov 27, 2023
2f14508
Clang tidy
sjahr Nov 27, 2023
0af9950
Update logger
sjahr Nov 28, 2023
26458a4
Merge branch 'main' into pr-enable_multiple_planners
sjahr Nov 28, 2023
339496d
Remove warning that reference trajectory is ignored in stomp
sjahr Nov 30, 2023
41f1ce0
Merge branch 'main' into pr-enable_multiple_planners
sjahr Dec 6, 2023
10c554e
clang-format
tylerjw Dec 6, 2023
f59379c
rebase logging api chainges
tylerjw Dec 6, 2023
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
7 changes: 7 additions & 0 deletions MIGRATION.md
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,13 @@
API changes in MoveIt releases

## ROS Rolling
- [10/2023] The planning pipeline now has a vector of planner plugins rather than a single one. Please update the planner plugin parameter e.g. like this:
```diff
- planning_plugin: ompl_interface/OMPLPlanner
+ planning_plugins:
+ - ompl_interface/OMPLPlanner
```

- [10/2023] Planning request adapters are now separated into PlanRequest (preprocessing) and PlanResponse (postprocessing) adapters. The adapters are configured with ROS parameter vectors (vector order corresponds to execution order). Please update your pipeline configurations for example like this:
```diff
- request_adapters: >-
Expand Down
3 changes: 2 additions & 1 deletion moveit_configs_utils/default_configs/chomp_planning.yaml
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
planning_plugin: chomp_interface/CHOMPPlanner
planning_plugins:
- chomp_interface/CHOMPPlanner
enable_failure_recovery: true
# The order of the elements in the adapter corresponds to the order they are processed by the motion planning pipeline.
request_adapters:
Expand Down
3 changes: 2 additions & 1 deletion moveit_configs_utils/default_configs/ompl_planning.yaml
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
planning_plugin: ompl_interface/OMPLPlanner
planning_plugins:
- ompl_interface/OMPLPlanner
# The order of the elements in the adapter corresponds to the order they are processed by the motion planning pipeline.
request_adapters:
- default_planning_request_adapters/ResolveConstraintFrames
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,14 @@
planning_plugin: pilz_industrial_motion_planner/CommandPlanner
# The order of the elements in the adapter corresponds to the order they are processed by the motion planning pipeline.
planning_plugins:
- pilz_industrial_motion_planner/CommandPlanner
default_planner_config: PTP
request_adapters:
- default_planning_request_adapters/ResolveConstraintFrames
- default_planning_request_adapters/ValidateWorkspaceBounds
- default_planning_request_adapters/CheckStartStateBounds
- default_planning_request_adapters/CheckStartStateCollision
response_adapters:
- default_planning_response_adapters/ValidateSolution
- default_planning_response_adapters/DisplayMotionPath
capabilities: >-
pilz_industrial_motion_planner/MoveGroupSequenceAction
pilz_industrial_motion_planner/MoveGroupSequenceService
4 changes: 2 additions & 2 deletions moveit_configs_utils/default_configs/stomp_planning.yaml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
planning_plugin: stomp_moveit/StompPlanner
# The order of the elements in the adapter corresponds to the order they are processed by the motion planning pipeline.
planning_plugins:
- stomp_moveit/StompPlanner
request_adapters:
- default_planning_request_adapters/ResolveConstraintFrames
- default_planning_request_adapters/ValidateWorkspaceBounds
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -164,8 +164,8 @@ class PlannerManager
virtual bool initialize(const moveit::core::RobotModelConstPtr& model, const rclcpp::Node::SharedPtr& node,
const std::string& parameter_namespace);

/// Get \brief a short string that identifies the planning interface
virtual std::string getDescription() const;
/// \brief Get a short string that identifies the planning interface.
virtual std::string getDescription() const = 0;

/// \brief Get the names of the known planning algorithms (values that can be filled as planner_id in the planning
/// request)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,8 @@ def generate_test_description():
# Load the context
test_config = load_moveit_config()

planning_plugin = {
"planning_plugin": "pilz_industrial_motion_planner/CommandPlanner"
planning_plugins = {
"planning_plugins": ["pilz_industrial_motion_planner/CommandPlanner"]
}

# run test
Expand All @@ -29,7 +29,7 @@ def generate_test_description():
name="unittest_pilz_industrial_motion_planner",
parameters=[
test_config.to_dict(),
planning_plugin,
planning_plugins,
],
output="screen",
)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -74,8 +74,8 @@ class CommandPlannerTest : public testing::Test
ASSERT_TRUE(bool(robot_model_)) << "Failed to load robot model";

// Load planner name from node parameters
ASSERT_TRUE(node_->has_parameter("planning_plugin")) << "Could not find parameter 'planning_plugin'";
node_->get_parameter<std::string>("planning_plugin", planner_plugin_name_);
ASSERT_TRUE(node_->has_parameter("planning_plugins")) << "Could not find parameter 'planning_plugins'";
node_->get_parameter<std::vector<std::string>>("planning_plugins", planner_plugin_names_);

// Load the plugin
try
Expand All @@ -92,7 +92,7 @@ class CommandPlannerTest : public testing::Test
// Create planner
try
{
planner_instance_.reset(planner_plugin_loader_->createUnmanagedInstance(planner_plugin_name_));
planner_instance_.reset(planner_plugin_loader_->createUnmanagedInstance(planner_plugin_names_.at(0)));
ASSERT_TRUE(planner_instance_->initialize(robot_model_, node_, ""))
<< "Initializing the planner instance failed.";
}
Expand All @@ -104,7 +104,7 @@ class CommandPlannerTest : public testing::Test

void TearDown() override
{
planner_plugin_loader_->unloadLibraryForClass(planner_plugin_name_);
planner_plugin_loader_->unloadLibraryForClass(planner_plugin_names_.at(0));
robot_model_.reset();
}

Expand All @@ -114,7 +114,7 @@ class CommandPlannerTest : public testing::Test
moveit::core::RobotModelConstPtr robot_model_;
std::unique_ptr<robot_model_loader::RobotModelLoader> rm_loader_;

std::string planner_plugin_name_;
std::vector<std::string> planner_plugin_names_;
std::unique_ptr<pluginlib::ClassLoader<planning_interface::PlannerManager>> planner_plugin_loader_;
planning_interface::PlannerManagerPtr planner_instance_;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -81,12 +81,20 @@ def generate_launch_description():
"default_planning_pipeline": "ompl",
"planning_pipelines": ["pilz", "ompl"],
"pilz": {
"planning_plugin": "pilz_industrial_motion_planner/CommandPlanner",
"request_adapters": "",
"planning_plugins": ["pilz_industrial_motion_planner/CommandPlanner"],
},
"ompl": {
"planning_plugin": "ompl_interface/OMPLPlanner",
"request_adapters": """default_planning_request_adapters/AddTimeOptimalParameterization default_planning_request_adapters/ValidateWorkspaceBounds default_planning_request_adapters/CheckStartStateBounds default_planning_request_adapters/CheckStartStateCollision default_planning_request_adapters/FixStartStatePathConstraints""",
"planning_plugins": ["ompl_interface/OMPLPlanner"],
"request_adapters": [
"default_planning_request_adapters/ResolveConstraintFrames",
"default_planning_request_adapters/ValidateWorkspaceBounds",
"default_planning_request_adapters/CheckStartStateBounds",
"default_planning_request_adapters/CheckStartStateCollision",
],
"response_adapters": [
"default_planning_response_adapters/AddTimeOptimalParameterization",
"default_planning_response_adapters/ValidateSolution",
],
},
}
ompl_planning_yaml = load_yaml(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -169,9 +169,8 @@ class BenchmarkExecutor

void shiftConstraintsByOffset(moveit_msgs::msg::Constraints& constraints, const std::vector<double>& offset);

/// Check that the desired planner plugins and algorithms exist for the given group
bool plannerConfigurationsExist(const std::map<std::string, std::vector<std::string>>& planners,
const std::string& group_name);
/// Check that the desired planning pipelines exist
bool pipelinesExist(const std::map<std::string, std::vector<std::string>>& planners);

/// Load the planning scene with the given name from the warehouse
bool loadPlanningScene(const std::string& scene_name, moveit_msgs::msg::PlanningScene& scene_msg);
Expand Down
46 changes: 4 additions & 42 deletions moveit_ros/benchmarks/src/BenchmarkExecutor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -114,7 +114,7 @@ BenchmarkExecutor::~BenchmarkExecutor()

const auto& pipeline = moveit_cpp_->getPlanningPipelines().at(planning_pipeline_name);
// Verify the pipeline has successfully initialized a planner
if (!pipeline->getPlannerManager())
if (!pipeline)
{
RCLCPP_ERROR(getLogger(), "Failed to initialize planning pipeline '%s'", planning_pipeline_name.c_str());
continue;
Expand All @@ -132,8 +132,7 @@ BenchmarkExecutor::~BenchmarkExecutor()
for (const std::pair<const std::string, planning_pipeline::PlanningPipelinePtr>& entry :
moveit_cpp_->getPlanningPipelines())
{
RCLCPP_INFO_STREAM(getLogger(),
"Pipeline: " << entry.first << ", Planner: " << entry.second->getPlannerPluginName());
RCLCPP_INFO_STREAM(getLogger(), entry.first);
}
}
return true;
Expand Down Expand Up @@ -260,7 +259,7 @@ bool BenchmarkExecutor::initializeBenchmarks(const BenchmarkOptions& options,
moveit_msgs::msg::PlanningScene& scene_msg,
std::vector<BenchmarkRequest>& requests)
{
if (!plannerConfigurationsExist(options.planning_pipelines, options.group_name))
if (!pipelinesExist(options.planning_pipelines))
{
return false;
}
Expand Down Expand Up @@ -521,8 +520,7 @@ void BenchmarkExecutor::createRequestCombinations(const BenchmarkRequest& benchm
}
}

bool BenchmarkExecutor::plannerConfigurationsExist(
const std::map<std::string, std::vector<std::string>>& pipeline_configurations, const std::string& group_name)
bool BenchmarkExecutor::pipelinesExist(const std::map<std::string, std::vector<std::string>>& pipeline_configurations)
{
// Make sure planner plugins exist
for (const std::pair<const std::string, std::vector<std::string>>& pipeline_config_entry : pipeline_configurations)
Expand All @@ -542,42 +540,6 @@ bool BenchmarkExecutor::plannerConfigurationsExist(
return false;
}
}

// Make sure planners exist within those pipelines
auto planning_pipelines = moveit_cpp_->getPlanningPipelines();
for (const std::pair<const std::string, std::vector<std::string>>& entry : pipeline_configurations)
{
planning_interface::PlannerManagerPtr pm = planning_pipelines[entry.first]->getPlannerManager();
const planning_interface::PlannerConfigurationMap& config_map = pm->getPlannerConfigurations();

// if the planner is chomp or stomp skip this function and return true for checking planner configurations for the
// planning group otherwise an error occurs, because for OMPL a specific planning algorithm needs to be defined for
// a planning group, whereas with STOMP and CHOMP this is not necessary
if (pm->getDescription().compare("stomp") || pm->getDescription().compare("chomp"))
continue;

for (std::size_t i = 0; i < entry.second.size(); ++i)
{
bool planner_exists = false;
for (const std::pair<const std::string, planning_interface::PlannerConfigurationSettings>& config_entry :
config_map)
{
std::string planner_name = group_name + "[" + entry.second[i] + "]";
planner_exists = (config_entry.second.group == group_name && config_entry.second.name == planner_name);
}

if (!planner_exists)
{
RCLCPP_ERROR(getLogger(), "Planner '%s' does NOT exist for group '%s' in pipeline '%s'",
entry.second[i].c_str(), group_name.c_str(), entry.first.c_str());
std::cout << "There are " << config_map.size() << " planner entries: " << '\n';
for (const auto& config_map_entry : config_map)
std::cout << config_map_entry.second.name << '\n';
return false;
}
}
}

return true;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ bool MoveItPlanningPipeline::initialize(const rclcpp::Node::SharedPtr& node)
node->declare_parameter<double>(PLAN_REQUEST_PARAM_NS + "planning_time", 1.0);
node->declare_parameter<double>(PLAN_REQUEST_PARAM_NS + "max_velocity_scaling_factor", 1.0);
node->declare_parameter<double>(PLAN_REQUEST_PARAM_NS + "max_acceleration_scaling_factor", 1.0);
node->declare_parameter<std::string>("ompl.planning_plugin", "ompl_interface/OMPLPlanner");
node->declare_parameter<std::vector<std::string>>("ompl.planning_plugins", { "ompl_interface/OMPLPlanner" });

// Planning Scene options
node->declare_parameter<std::string>(PLANNING_SCENE_MONITOR_NS + "name", UNDEFINED);
Expand Down
14 changes: 12 additions & 2 deletions moveit_ros/hybrid_planning/test/launch/hybrid_planning_common.py
Original file line number Diff line number Diff line change
Expand Up @@ -70,8 +70,18 @@ def generate_common_hybrid_launch_description():
# The global planner uses the typical OMPL parameters
planning_pipelines_config = {
"ompl": {
"planning_plugin": "ompl_interface/OMPLPlanner",
"request_adapters": """default_planning_request_adapters/AddTimeOptimalParameterization default_planning_request_adapters/ValidateWorkspaceBounds default_planning_request_adapters/CheckStartStateBounds default_planning_request_adapters/CheckStartStateCollision""",
"planning_plugins": ["ompl_interface/OMPLPlanner"],
"request_adapters": [
"default_planning_request_adapters/ResolveConstraintFrames",
"default_planning_request_adapters/ValidateWorkspaceBounds",
"default_planning_request_adapters/CheckStartStateBounds",
"default_planning_request_adapters/CheckStartStateCollision",
],
"response_adapters": [
"default_planning_response_adapters/AddTimeOptimalParameterization",
"default_planning_response_adapters/ValidateSolution",
"default_planning_response_adapters/DisplayMotionPath",
],
}
}
ompl_planning_yaml = load_yaml(
Expand Down
Loading
Loading