Skip to content

Commit

Permalink
Address review
Browse files Browse the repository at this point in the history
  • Loading branch information
sjahr committed Oct 16, 2023
1 parent a3431eb commit e9e2342
Show file tree
Hide file tree
Showing 12 changed files with 23 additions and 118 deletions.
1 change: 1 addition & 0 deletions moveit_configs_utils/default_configs/chomp_planning.yaml
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
planning_plugin: chomp_interface/CHOMPPlanner
enable_failure_recovery: true
jiggle_fraction: 0.05
# The order of the elements in the adapter corresponds to the order they are processed by the motion planning pipeline.
request_adapters:
- default_planner_request_adapters/ResolveConstraintFrames
- default_planner_request_adapters/FixWorkspaceBounds
Expand Down
1 change: 1 addition & 0 deletions moveit_configs_utils/default_configs/ompl_planning.yaml
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
planning_plugin: ompl_interface/OMPLPlanner
start_state_max_bounds_error: 0.1
jiggle_fraction: 0.05
# The order of the elements in the adapter corresponds to the order they are processed by the motion planning pipeline.
request_adapters:
- default_planner_request_adapters/ResolveConstraintFrames
- default_planner_request_adapters/FixWorkspaceBounds
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
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.
request_adapters: ""
default_planner_config: PTP
capabilities: >-
Expand Down
1 change: 1 addition & 0 deletions moveit_configs_utils/default_configs/stomp_planning.yaml
Original file line number Diff line number Diff line change
@@ -1,4 +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.
request_adapters:
- default_planner_request_adapters/ResolveConstraintFrames
- default_planner_request_adapters/FixWorkspaceBounds
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,6 @@

#include <moveit/macros/class_forward.h>
#include <moveit/planning_interface/planning_interface.h>
#include <functional>
#include <rclcpp/logging.hpp>
#include <rclcpp/node.hpp>

Expand Down
6 changes: 0 additions & 6 deletions moveit_planners/stomp/stomp_moveit_plugin_description.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,4 @@
STOMP Motion Planning Plugin for MoveIt
</description>
</class>
<class name="stomp_moveit/StompSmoothingAdapter" type="stomp_moveit::StompSmoothingAdapter"
base_class_type="planning_interface::PlanningRequestAdapter">
<description>
STOMP Smoothing Adapter for MoveIt
</description>
</class>
</library>
Original file line number Diff line number Diff line change
@@ -1,10 +1,5 @@
<library path="moveit_default_planning_request_adapter_plugins">

<class name="default_planner_request_adapters/Empty" type="default_planner_request_adapters::Empty" base_class_type="planning_interface::PlanningRequestAdapter">
<description>
</description>
</class>

<class name="default_planner_request_adapters/FixStartStateBounds" type="default_planner_request_adapters::FixStartStateBounds" base_class_type="planning_interface::PlanningRequestAdapter">
<description>
</description>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

<class name="default_planner_response_adapters/AddTimeOptimalParameterization" type="default_planner_response_adapters::AddTimeOptimalParameterization" base_class_type="planning_interface::PlanningResponseAdapter">
<description>
This is an improved time parameterization using Time-Optimal Trajectory Generation for Path Following With Bounded Acceleration and Velocity (Kunz and Stilman, RSS 2008). Assumes starting and ending at rest. Not jerk limited.
Time parameterization using Time-Optimal Trajectory Generation for Path Following With Bounded Acceleration and Velocity (Kunz and Stilman, RSS 2008). Assumes starting and ending at rest. Not jerk limited.
</description>
</class>

Expand Down
10 changes: 0 additions & 10 deletions moveit_ros/planning/introspection/CMakeLists.txt

This file was deleted.

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -126,10 +126,11 @@ void loadPluginVector(const std::shared_ptr<rclcpp::Node>& node,
}
else
{
RCLCPP_WARN(node->get_logger(), "Failed to load adapter '%s'", plugin_name.c_str());
RCLCPP_WARN(node->get_logger(), "Failed to initialize adapter '%s'", plugin_name.c_str());
}
}
};

} // namespace
/** \brief This class facilitates loading planning plugins and planning adapter plugins. It implements functionality to
* use the loaded plugins in a motion planning pipeline consisting of PlanningRequestAdapters (Pre-processing), a
Expand All @@ -149,19 +150,25 @@ class MOVEIT_PLANNING_PIPELINE_EXPORT PlanningPipeline

/** \brief Given a robot model, a ROS node and a parameter namespace, initialize the planning pipeline. The planner plugin
and adapters are provided in form of ROS parameters. The order of the elements in the adapter vectors corresponds
to the order in the motion planning pipeline. \param model The robot model for which this pipeline is initialized.
\param node The ROS node that should be used for reading parameters needed for configuration
\param parameter_namespace parameter namespace where the planner configurations are stored
to the order in the motion planning pipeline.
\param model The robot model for which this pipeline is initialized.
\param node The ROS node that should be used for reading parameters needed for configuration
\param parameter_namespace parameter namespace where the planner configurations are stored
*/
PlanningPipeline(const moveit::core::RobotModelConstPtr& model, const std::shared_ptr<rclcpp::Node>& node,
const std::string& parameter_namespace);

/** \brief Given a robot model, a ROS node and a parameter namespace, initialize the planning pipeline with the given
planner plugin and adapters. The order of the elements in the adapter vectors corresponds to the order in the
motion planning pipeline. \param model The robot model for which this pipeline is initialized. \param node The ROS
node that should be used for reading parameters needed for configuration \param parameter_namespace Parameter
namespace where the planner configurations are stored \param request_adapter_plugin_names Optional vector of
RequestAdapter plugin names \param response_adapter_plugin_names Optional vector of ResponseAdapter plugin names
motion planning pipeline.
\param model The robot model for which this pipeline is initialized.
\param node The ROS
node that should be used for reading parameters needed for configuration
\param parameter_namespace Parameter
namespace where the planner configurations are stored
\param request_adapter_plugin_names Optional vector of
RequestAdapter plugin names
\param response_adapter_plugin_names Optional vector of ResponseAdapter plugin names
*/
PlanningPipeline(const moveit::core::RobotModelConstPtr& model, const std::shared_ptr<rclcpp::Node>& node,
const std::string& parameter_namespace, const std::string& planning_plugin_name,
Expand Down Expand Up @@ -228,7 +235,7 @@ class MOVEIT_PLANNING_PIPELINE_EXPORT PlanningPipeline
return pipeline_parameters_.request_adapters;
}

/** \brief Get the names of the planning response adapter plugins used */
/** \brief Get the names of the planning response adapter plugins in the order they are processed. */
[[nodiscard]] const std::vector<std::string>& getResponseAdapterPluginNames() const
{
return pipeline_parameters_.response_adapters;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,11 +6,11 @@ planning_pipeline_parameters:
}
request_adapters: {
type: string_array,
description: "Names of the planning request adapter plugins (Order in chain is similar to array order).",
description: "Names of the planning request adapter plugins (plugin names separated by space). The order of the elements in the adapter corresponds to the order they are processed by the motion planning pipeline..",
default_value: [],
}
response_adapters: {
type: string_array,
description: "Names of the planning request adapter plugins (Order in chain is similar to array order).",
description: "Names of the planning request adapter plugins (plugin names separated by space). The order of the elements in the adapter corresponds to the order they are processed by the motion planning pipeline.",
default_value: [],
}

0 comments on commit e9e2342

Please sign in to comment.