Skip to content

Commit

Permalink
Refactor planning pipeline chain
Browse files Browse the repository at this point in the history
Move plan_request_adapters into planning interface package

Add callRequestAdapterChain function

Differentiate between request and response adapters

Restore planning_pipeline.cpp

Add response_adapters parameter and cleanup adapter chain calls

Add response adapter loading chain

Address compiler errors

Fix parameter type

Fix compilation errors

Rename planning_request_adapters to *_adapter

Cleanup + fix errors

Fix plugins and print description

Remove unused adapters

Planners plan, Adapters adapt ...

Format + fix compilation error

Simplify by removing callRequest/ResponseAdapterChain

Remove unneeded PlannerFn

Make clang tidy happy

Add loadPluginVector template and make callAdapterChain private

Add documentation

Remove TODOs

Cleanups and move templates into annonymous namespace

Add more debug information and fix bugs in adapters

Fix bugs

Remove commented out CMake lines

Update parameter description

Apply suggestions from code review

Co-authored-by: Abishalini Sivaraman <[email protected]>

Address review

Remove instrospection dir

Make parameters read only

Make sure that pipeline does not abort if no request adapter is configured

Remove anonymous namespace in header

Move adapter params into separate namespace

Delete outdated unittest
  • Loading branch information
sjahr committed Oct 23, 2023
1 parent 15d9d61 commit 1992fe5
Show file tree
Hide file tree
Showing 43 changed files with 494 additions and 1,683 deletions.
15 changes: 8 additions & 7 deletions moveit_configs_utils/default_configs/chomp_planning.yaml
Original file line number Diff line number Diff line change
@@ -1,12 +1,13 @@
planning_plugin: chomp_interface/CHOMPPlanner
enable_failure_recovery: true
jiggle_fraction: 0.05
request_adapters: >-
default_planner_request_adapters/AddTimeOptimalParameterization
default_planner_request_adapters/ResolveConstraintFrames
default_planner_request_adapters/FixWorkspaceBounds
default_planner_request_adapters/FixStartStateBounds
default_planner_request_adapters/FixStartStateCollision
default_planner_request_adapters/FixStartStatePathConstraints
# 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
- default_planner_request_adapters/FixStartStateBounds
- default_planner_request_adapters/FixStartStateCollision
response_adapters:
- default_planner_response_adapters/AddTimeOptimalParameterization
ridge_factor: 0.01
start_state_max_bounds_error: 0.1
15 changes: 8 additions & 7 deletions moveit_configs_utils/default_configs/ompl_planning.yaml
Original file line number Diff line number Diff line change
@@ -1,10 +1,11 @@
planning_plugin: ompl_interface/OMPLPlanner
start_state_max_bounds_error: 0.1
jiggle_fraction: 0.05
request_adapters: >-
default_planner_request_adapters/AddTimeOptimalParameterization
default_planner_request_adapters/ResolveConstraintFrames
default_planner_request_adapters/FixWorkspaceBounds
default_planner_request_adapters/FixStartStateBounds
default_planner_request_adapters/FixStartStateCollision
default_planner_request_adapters/FixStartStatePathConstraints
# 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
- default_planner_request_adapters/FixStartStateBounds
- default_planner_request_adapters/FixStartStateCollision
response_adapters:
- default_planner_response_adapters/AddTimeOptimalParameterization
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
15 changes: 8 additions & 7 deletions moveit_configs_utils/default_configs/stomp_planning.yaml
Original file line number Diff line number Diff line change
@@ -1,11 +1,12 @@
planning_plugin: stomp_moveit/StompPlanner
request_adapters: >-
default_planner_request_adapters/AddTimeOptimalParameterization
default_planner_request_adapters/ResolveConstraintFrames
default_planner_request_adapters/FixWorkspaceBounds
default_planner_request_adapters/FixStartStateBounds
default_planner_request_adapters/FixStartStateCollision
default_planner_request_adapters/FixStartStatePathConstraints
# 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
- default_planner_request_adapters/FixStartStateBounds
- default_planner_request_adapters/FixStartStateCollision
response_adapters:
- default_planner_response_adapters/AddTimeOptimalParameterization

stomp_moveit:
num_timesteps: 60
Expand Down
2 changes: 0 additions & 2 deletions moveit_core/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,6 @@ add_subdirectory(kinematics_metrics)
add_subdirectory(macros)
add_subdirectory(online_signal_smoothing)
add_subdirectory(planning_interface)
add_subdirectory(planning_request_adapter)
add_subdirectory(planning_scene)
add_subdirectory(robot_model)
add_subdirectory(robot_state)
Expand Down Expand Up @@ -115,7 +114,6 @@ install(
moveit_kinematics_metrics
moveit_macros
moveit_planning_interface
moveit_planning_request_adapter
moveit_planning_scene
moveit_robot_model
moveit_robot_state
Expand Down
1 change: 1 addition & 0 deletions moveit_core/planning_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@ ament_target_dependencies(moveit_planning_interface
target_link_libraries(moveit_planning_interface
moveit_robot_trajectory
moveit_robot_state
moveit_planning_scene
moveit_utils
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,16 +39,12 @@
#include <moveit/macros/class_forward.h>
#include <moveit/planning_interface/planning_request.h>
#include <moveit/planning_interface/planning_response.h>
#include <moveit/planning_scene/planning_scene.h>
#include <rclcpp/node.hpp>
#include <string>
#include <map>
#include <rclcpp/rclcpp.hpp>

namespace planning_scene
{
MOVEIT_CLASS_FORWARD(PlanningScene); // Defines PlanningScenePtr, ConstPtr, WeakPtr... etc
}

/** \brief This namespace includes the base class for MoveIt planners */
namespace planning_interface
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,19 +32,18 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

/* Author: Ioan Sucan */
/* Author: Ioan Sucan, Sebastian Jahr
Description: Generic interface to adapting motion planning requests
*/

#pragma once

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

/** \brief Generic interface to adapting motion planning requests */
namespace planning_request_adapter
namespace planning_interface
{
MOVEIT_CLASS_FORWARD(PlanningRequestAdapter); // Defines PlanningRequestAdapterPtr, ConstPtr, WeakPtr... etc

Expand All @@ -55,11 +54,6 @@ MOVEIT_CLASS_FORWARD(PlanningRequestAdapter); // Defines PlanningRequestAdapter
class PlanningRequestAdapter
{
public:
/// \brief Functional interface to call a planning function
using PlannerFn =
std::function<bool(const planning_scene::PlanningSceneConstPtr&, const planning_interface::MotionPlanRequest&,
planning_interface::MotionPlanResponse&)>;

/** \brief Initialize parameters using the passed Node and parameter namespace.
* @param node Node instance used by the adapter
* @param parameter_namespace Parameter namespace for adapter
Expand All @@ -76,52 +70,12 @@ class PlanningRequestAdapter
needed. If the response is changed, the index values of the
states added without planning are added to \e
added_path_index
* @param planner Pointer to the planner used to solve the passed problem
* @param planning_scene Representation of the environment for the planning
* @param req Motion planning request with a set of constraints
* @param res Reference to which the generated motion plan response is written to
* @return True if response got generated correctly */
[[nodiscard]] bool adaptAndPlan(const planning_interface::PlannerManagerPtr& planner,
const planning_scene::PlanningSceneConstPtr& planning_scene,
const planning_interface::MotionPlanRequest& req,
planning_interface::MotionPlanResponse& res) const;

/** \brief Adapt the planning request if needed, call the planner
function \e planner and update the planning response if
needed. If the response is changed, the index values of the
states added without planning are added to \e
added_path_index
* @param planner Pointer to the planner used to solve the passed problem
* @param planning_scene Representation of the environment for the planning
* @param req Motion planning request with a set of constraints
* @param res Reference to which the generated motion plan response is written to
* @return True if response got generated correctly */
[[nodiscard]] virtual bool adaptAndPlan(const PlannerFn& planner,
const planning_scene::PlanningSceneConstPtr& planning_scene,
const planning_interface::MotionPlanRequest& req,
planning_interface::MotionPlanResponse& res) const = 0;
};

/** \brief Apply a sequence of adapters to a motion plan */
class PlanningRequestAdapterChain
{
public:
/** \brief Add new adapter to the back of the chain
* @param adapter Adapter to be added */
void addAdapter(const PlanningRequestAdapterConstPtr& adapter);

/** \brief Iterate through the chain and call all adapters and planners in the correct order
* @param planner Pointer to the planner used to solve the passed problem
* @param planning_scene Representation of the environment for the planning
* @param req Motion planning request with a set of constraints
* @param res Reference to which the generated motion plan response is written to
* @return True if response got generated correctly */
[[nodiscard]] bool adaptAndPlan(const planning_interface::PlannerManagerPtr& planner,
const planning_scene::PlanningSceneConstPtr& planning_scene,
const planning_interface::MotionPlanRequest& req,
planning_interface::MotionPlanResponse& res) const;

private:
std::vector<PlanningRequestAdapterConstPtr> adapters_;
[[nodiscard]] virtual bool adapt(const planning_scene::PlanningSceneConstPtr& planning_scene,
planning_interface::MotionPlanRequest& req,
const planning_interface::MotionPlanResponse& res) const = 0;
};
} // namespace planning_request_adapter
} // namespace planning_interface
Original file line number Diff line number Diff line change
@@ -0,0 +1,80 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2023, PickNik Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of PickNik Inc. nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

/* Author: Sebastian Jahr */

#pragma once

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

namespace planning_interface
{
MOVEIT_CLASS_FORWARD(PlanningResponseAdapter); // Defines PlanningResponseAdapterPtr, ConstPtr, WeakPtr... etc

/** @brief Concept in MoveIt which can be used to modify the planning problem and resulting trajectory (pre-processing
* and/or post-processing) for a motion planner. PlanningResponseAdapter enable using multiple motion planning and
* trajectory generation algorithms in sequence to produce robust motion plans.
*/
class PlanningResponseAdapter
{
public:
/** \brief Initialize parameters using the passed Node and parameter namespace.
* @param node Node instance used by the adapter
* @param parameter_namespace Parameter namespace for adapter
If no initialization is needed, simply implement as empty */
virtual void initialize(const rclcpp::Node::SharedPtr& node, const std::string& parameter_namespace) = 0;

/** \brief Get a description of this adapter
* @return Returns a short string that identifies the planning response adapter
*/
[[nodiscard]] virtual std::string getDescription() const = 0;

/** \brief Adapt the planning request if needed, call the planner
function \e planner and update the planning response if
needed. If the response is changed, the index values of the
states added without planning are added to \e
added_path_index
* @param planner Pointer to the planner used to solve the passed problem
* @param planning_scene Representation of the environment for the planning
* @param req Motion planning request with a set of constraints
* @param res Reference to which the generated motion plan response is written to
* @return True if response got generated correctly */
[[nodiscard]] virtual bool adapt(const planning_scene::PlanningSceneConstPtr& planning_scene,
const planning_interface::MotionPlanRequest& req,
planning_interface::MotionPlanResponse& res) const = 0;
};
} // namespace planning_interface
28 changes: 0 additions & 28 deletions moveit_core/planning_request_adapter/CMakeLists.txt

This file was deleted.

Loading

0 comments on commit 1992fe5

Please sign in to comment.