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

Cleanup planning request adapter interface #2266

Merged
Merged
Show file tree
Hide file tree
Changes from 7 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
Expand Up @@ -46,6 +46,10 @@
/** \brief Generic interface to adapting motion planning requests */
namespace planning_request_adapter
{
namespace
{
std::vector<std::size_t> EMPTY_PATH_INDEX_VECTOR = {};
}
MOVEIT_CLASS_FORWARD(PlanningRequestAdapter); // Defines PlanningRequestAdapterPtr, ConstPtr, WeakPtr... etc

/** @brief Concept in MoveIt which can be used to modify the planning problem and resulting trajectory (pre-processing
Expand All @@ -60,8 +64,6 @@ class PlanningRequestAdapter
std::function<bool(const planning_scene::PlanningSceneConstPtr&, const planning_interface::MotionPlanRequest&,
planning_interface::MotionPlanResponse&)>;

virtual ~PlanningRequestAdapter() = default;

/** \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 @@ -71,23 +73,7 @@ class PlanningRequestAdapter
/** \brief Get a description of this adapter
* @return Returns a short string that identifies the planning request adapter
*/
virtual std::string getDescription() const
{
return "";
}

/** \brief Adapt the planning request if needed, call the planner
function \e planner and update the planning response if
needed.
* @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 */
bool adaptAndPlan(const planning_interface::PlannerManagerPtr& planner,
const planning_scene::PlanningSceneConstPtr& planning_scene,
const planning_interface::MotionPlanRequest& req,
planning_interface::MotionPlanResponse& res) const;
[[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
Expand All @@ -103,10 +89,11 @@ class PlanningRequestAdapter
current state itself appears to touch obstacles). This is helpful because the added states should not be considered
invalid in all situations.
* @return True if response got generated correctly */
bool adaptAndPlan(const planning_interface::PlannerManagerPtr& planner,
const planning_scene::PlanningSceneConstPtr& planning_scene,
const planning_interface::MotionPlanRequest& req, planning_interface::MotionPlanResponse& res,
std::vector<std::size_t>& added_path_index) const;
[[nodiscard]] bool adaptAndPlan(const planning_interface::PlannerManagerPtr& planner,
const planning_scene::PlanningSceneConstPtr& planning_scene,
const planning_interface::MotionPlanRequest& req,
planning_interface::MotionPlanResponse& res,
std::vector<std::size_t>& added_path_index = EMPTY_PATH_INDEX_VECTOR) const;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This pattern of passing the default std::vector<std::size_t>& added_path_index = EMPTY_PATH_INDEX_VECTOR isn't making sense to me. It is an out-parameter? If the user doesn't pass their own, does it not mutate the global EMPTY_PATH_INDEX_VECTOR, which surely is not the intent?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Also note that clang-tidy CI is complaining about the naming of this and failing.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

My intend with this was to remove these functions:

bool PlanningRequestAdapterChain::adaptAndPlan(const planning_interface::PlannerManagerPtr& planner,
                                               const planning_scene::PlanningSceneConstPtr& planning_scene,
                                               const planning_interface::MotionPlanRequest& req,
                                               planning_interface::MotionPlanResponse& res) const
{
  std::vector<std::size_t> empty_added_path_index;
  return adaptAndPlan(planner, planning_scene, req, res, empty_added_path_index);
}

As far as I understand there are no optional references, so like before we just write the path indices to a memory location we never read and dump them that way. Maybe another possible implementation would be to change this interface to use a pointer but that would be a bigger change. Do you have a smarter idea of how to do this?

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

can't you just use std::vector<std::size_t>& added_path_index = {}?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@henningkayser C++ won't let you assign a default reference like that.

@sjahr I guess this pattern will technically work as long as adaptAndPlan makes sure to clear the "empty" vector before it starts every time. Otherwise it's a memory leak!

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

oh of course not... content-wise, this parameter would fit into the MotionPlanResponse as well, or at least the detailed response. I wouldn't sweat it too much since we should take another close look at this interface anyway.


/** \brief Adapt the planning request if needed, call the planner
function \e planner and update the planning response if
Expand All @@ -122,31 +109,10 @@ class PlanningRequestAdapter
current state itself appears to touch obstacles). This is helpful because the added states should not be
considered invalid in all situations.
* @return True if response got generated correctly */
virtual bool adaptAndPlan(const PlannerFn& planner, const planning_scene::PlanningSceneConstPtr& planning_scene,
const planning_interface::MotionPlanRequest& req,
planning_interface::MotionPlanResponse& res,
std::vector<std::size_t>& added_path_index) const = 0;

protected:
/** \brief Helper param for getting a parameter using a namespace **/
template <typename T>
T getParam(const rclcpp::Node::SharedPtr& node, const rclcpp::Logger& logger, const std::string& parameter_namespace,
const std::string& parameter_name, T default_value = {}) const
{
std::string full_name = parameter_namespace.empty() ? parameter_name : parameter_namespace + "." + parameter_name;
T value;
if (!node->get_parameter(full_name, value))
{
RCLCPP_INFO(logger, "Param '%s' was not set. Using default value: %s", full_name.c_str(),
std::to_string(default_value).c_str());
return default_value;
}
else
{
RCLCPP_INFO(logger, "Param '%s' was set to %s", full_name.c_str(), std::to_string(value).c_str());
return value;
}
}
[[nodiscard]] virtual bool
adaptAndPlan(const PlannerFn& planner, const planning_scene::PlanningSceneConstPtr& planning_scene,
const planning_interface::MotionPlanRequest& req, planning_interface::MotionPlanResponse& res,
std::vector<std::size_t>& added_path_index = EMPTY_PATH_INDEX_VECTOR) const = 0;
};

/** \brief Apply a sequence of adapters to a motion plan */
Expand All @@ -157,17 +123,6 @@ class PlanningRequestAdapterChain
* @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 */
bool adaptAndPlan(const planning_interface::PlannerManagerPtr& planner,
const planning_scene::PlanningSceneConstPtr& planning_scene,
const planning_interface::MotionPlanRequest& req,
planning_interface::MotionPlanResponse& res) const;

/** \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
Expand All @@ -178,10 +133,11 @@ class PlanningRequestAdapterChain
current state itself appears to touch obstacles). This is helpful because the added states should not be
considered invalid in all situations.
* @return True if response got generated correctly */
bool adaptAndPlan(const planning_interface::PlannerManagerPtr& planner,
const planning_scene::PlanningSceneConstPtr& planning_scene,
const planning_interface::MotionPlanRequest& req, planning_interface::MotionPlanResponse& res,
std::vector<std::size_t>& added_path_index) const;
[[nodiscard]] bool adaptAndPlan(const planning_interface::PlannerManagerPtr& planner,
const planning_scene::PlanningSceneConstPtr& planning_scene,
const planning_interface::MotionPlanRequest& req,
planning_interface::MotionPlanResponse& res,
std::vector<std::size_t>& added_path_index = EMPTY_PATH_INDEX_VECTOR) const;

private:
std::vector<PlanningRequestAdapterConstPtr> adapters_;
Expand Down
Expand Up @@ -98,29 +98,11 @@ bool PlanningRequestAdapter::adaptAndPlan(const planning_interface::PlannerManag
planning_scene, req, res, added_path_index);
}

bool PlanningRequestAdapter::adaptAndPlan(const planning_interface::PlannerManagerPtr& planner,
const planning_scene::PlanningSceneConstPtr& planning_scene,
const planning_interface::MotionPlanRequest& req,
planning_interface::MotionPlanResponse& res) const
{
std::vector<std::size_t> empty_added_path_index;
return adaptAndPlan(planner, planning_scene, req, res, empty_added_path_index);
}

void PlanningRequestAdapterChain::addAdapter(const PlanningRequestAdapterConstPtr& adapter)
{
adapters_.push_back(adapter);
}

bool PlanningRequestAdapterChain::adaptAndPlan(const planning_interface::PlannerManagerPtr& planner,
const planning_scene::PlanningSceneConstPtr& planning_scene,
const planning_interface::MotionPlanRequest& req,
planning_interface::MotionPlanResponse& res) const
{
std::vector<std::size_t> empty_added_path_index;
return adaptAndPlan(planner, planning_scene, req, res, empty_added_path_index);
}

bool PlanningRequestAdapterChain::adaptAndPlan(const planning_interface::PlannerManagerPtr& planner,
const planning_scene::PlanningSceneConstPtr& planning_scene,
const planning_interface::MotionPlanRequest& req,
Expand Down
14 changes: 8 additions & 6 deletions moveit_ros/planning/CMakeLists.txt
Expand Up @@ -52,6 +52,7 @@ set(THIS_PACKAGE_LIBRARIES
moveit_plan_execution
moveit_planning_scene_monitor
moveit_collision_plugin_loader
default_plan_request_adapter_parameters
moveit_default_planning_request_adapter_plugins
moveit_cpp
)
Expand Down Expand Up @@ -79,19 +80,20 @@ include_directories(${THIS_PACKAGE_INCLUDE_DIRS})
include_directories(SYSTEM
${EIGEN3_INCLUDE_DIRS})

add_subdirectory(rdf_loader)
add_subdirectory(collision_plugin_loader)
add_subdirectory(kinematics_plugin_loader)
add_subdirectory(robot_model_loader)
add_subdirectory(constraint_sampler_manager_loader)
add_subdirectory(introspection)
add_subdirectory(kinematics_plugin_loader)
add_subdirectory(moveit_cpp)
add_subdirectory(plan_execution)
add_subdirectory(planning_components_tools)
add_subdirectory(planning_pipeline)
add_subdirectory(planning_pipeline_interfaces)
add_subdirectory(planning_request_adapter_plugins)
add_subdirectory(planning_scene_monitor)
add_subdirectory(planning_components_tools)
add_subdirectory(rdf_loader)
add_subdirectory(robot_model_loader)
add_subdirectory(trajectory_execution_manager)
add_subdirectory(plan_execution)
add_subdirectory(moveit_cpp)

install(
TARGETS ${THIS_PACKAGE_LIBRARIES}
Expand Down
11 changes: 11 additions & 0 deletions moveit_ros/planning/introspection/CMakeLists.txt
@@ -0,0 +1,11 @@
add_executable(moveit_list_planning_adapter_plugins src/list_planning_adapter_plugins.cpp)
ament_target_dependencies(moveit_list_planning_adapter_plugins
Boost
sjahr marked this conversation as resolved.
Show resolved Hide resolved
sjahr marked this conversation as resolved.
Show resolved Hide resolved
moveit_core
rclcpp
pluginlib
)

install(TARGETS moveit_list_planning_adapter_plugins
DESTINATION lib/${PROJECT_NAME}
)
Expand Up @@ -32,7 +32,10 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

/* Author: Ioan Sucan */
/* Author: Ioan Sucan
* Desc: Simple executable to list the loadable PlanningRequestAdapter. To use it simply run:
* `ros2 run moveit_ros_planning moveit_list_planning_adapter_plugins`
*/

#include <pluginlib/class_loader.hpp>
#include <moveit/planning_request_adapter/planning_request_adapter.h>
Expand Down
@@ -1,4 +1,6 @@
set(SOURCE_FILES
generate_parameter_library(default_plan_request_adapter_parameters res/default_plan_request_adapter_params.yaml)

add_library(moveit_default_planning_request_adapter_plugins SHARED
src/empty.cpp
src/fix_start_state_bounds.cpp
src/fix_start_state_collision.cpp
Expand All @@ -9,7 +11,7 @@ set(SOURCE_FILES
src/resolve_constraint_frames.cpp
)

add_library(moveit_default_planning_request_adapter_plugins SHARED ${SOURCE_FILES})
target_link_libraries(moveit_default_planning_request_adapter_plugins default_plan_request_adapter_parameters)

sjahr marked this conversation as resolved.
Show resolved Hide resolved
set_target_properties(moveit_default_planning_request_adapter_plugins PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")
ament_target_dependencies(moveit_default_planning_request_adapter_plugins
Expand All @@ -18,15 +20,3 @@ ament_target_dependencies(moveit_default_planning_request_adapter_plugins
rclcpp
pluginlib
)

add_executable(moveit_list_request_adapter_plugins src/list.cpp)
ament_target_dependencies(moveit_list_request_adapter_plugins
Boost
moveit_core
rclcpp
pluginlib
)

install(TARGETS moveit_list_request_adapter_plugins
DESTINATION lib/${PROJECT_NAME}
)
@@ -0,0 +1,44 @@
default_plan_request_adapter_parameters:
sjahr marked this conversation as resolved.
Show resolved Hide resolved
path_tolerance: {
type: double,
description: "AddTimeOptimalParameterization: Tolerance per joint in which the time parameterization is allowed to deviate from the original path.",
default_value: 0.1,
}
resample_dt: {
type: double,
description: "AddTimeOptimalParameterization: Time steps between two waypoints of the parameterized trajectory. The trajectory is re-sampled from the original path.",
sjahr marked this conversation as resolved.
Show resolved Hide resolved
default_value: 0.1,
}
min_angle_change: {
sjahr marked this conversation as resolved.
Show resolved Hide resolved
type: double,
description: "min_angle_change: ?",
sjahr marked this conversation as resolved.
Show resolved Hide resolved
default_value: 0.001,
}
start_state_max_dt: {
type: double,
description: "FixStartStateCollision/FixStartStateBounds: Maximum temporal distance of the fixed start state from the original state.",
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

How is this temporal distance computed? As a user, it's now clear to me how to set this parameter because there is no context about how the trajectory to the fixed start state from the original state is derived.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It is not computed but heuristically chosen:

// heuristically decide a duration offset for the trajectory (induced by the additional point added as a
// prefix to the computed trajectory)
res.trajectory->setWayPointDurationFromPrevious(0, std::min(params.start_state_max_dt,
                                                                      res.trajectory->getAverageSegmentDuration()));

Looking at this it might be worth creating a follow-up PR to change this to something that respects the joint limits & take spatial distance into account 🤔

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ok, maybe there is more than the parameter description lets on but it probably belongs in a follow-up.

default_value: 0.5,
}
jiggle_fraction: {
type: double,
description: "FixStartStateCollision: ?",
sjahr marked this conversation as resolved.
Show resolved Hide resolved
default_value: 0.02,
}
max_sampling_attempts: {
type: int,
description: "FixStartStateCollision: Maximum number of attempts to re-sample a valid start state.",
default_value: 100,
validation: {
bounds<>: [0, 255]
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why the upper bound here? Maybe I want to sample all day... 😄

Copy link
Contributor Author

@sjahr sjahr Jul 25, 2023

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Good point, I've updated that.
upper_bound_gone

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

in that case, does the adapter take care of timeouts? If not, unlimited sampling wouldn't be too useful

}
}
start_state_max_bounds_error: {
type: double,
description: "FixStartStateBounds: ?",
sjahr marked this conversation as resolved.
Show resolved Hide resolved
default_value: 0.05,
}
default_workspace_bounds: {
type: double,
description: "FixWorkspaceBounds: Default workspace bounds representing a cube around the robot's origin whose edge length this parameter defines.",
default_value: 10.0,
}
sjahr marked this conversation as resolved.
Show resolved Hide resolved
Expand Up @@ -52,10 +52,6 @@ static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_ros.add_traj_smo
class AddRuckigTrajectorySmoothing : public planning_request_adapter::PlanningRequestAdapter
{
public:
AddRuckigTrajectorySmoothing() : planning_request_adapter::PlanningRequestAdapter()
{
}

void initialize(const rclcpp::Node::SharedPtr& /* unused */, const std::string& /* unused */) override
{
}
Expand Down
Expand Up @@ -38,6 +38,8 @@
#include <moveit/trajectory_processing/time_optimal_trajectory_generation.h>
#include <class_loader/class_loader.hpp>

#include <default_plan_request_adapter_parameters.hpp>

namespace default_planner_request_adapters
{
using namespace trajectory_processing;
Expand All @@ -48,15 +50,10 @@ static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_ros.add_time_opt
class AddTimeOptimalParameterization : public planning_request_adapter::PlanningRequestAdapter
{
public:
AddTimeOptimalParameterization() : planning_request_adapter::PlanningRequestAdapter()
{
}

void initialize(const rclcpp::Node::SharedPtr& node, const std::string& parameter_namespace) override
{
path_tolerance_ = getParam(node, LOGGER, parameter_namespace, "path_tolerance", 0.1);
resample_dt_ = getParam(node, LOGGER, parameter_namespace, "resample_dt", 0.1);
min_angle_change_ = getParam(node, LOGGER, parameter_namespace, "min_angle_change", 0.001);
param_listener_ =
std::make_shared<default_plan_request_adapter_parameters::ParamListener>(node, parameter_namespace);
}

std::string getDescription() const override
Expand All @@ -72,7 +69,8 @@ class AddTimeOptimalParameterization : public planning_request_adapter::Planning
if (result && res.trajectory)
{
RCLCPP_DEBUG(LOGGER, " Running '%s'", getDescription().c_str());
TimeOptimalTrajectoryGeneration totg(path_tolerance_, resample_dt_, min_angle_change_);
const auto params = param_listener_->get_params();
TimeOptimalTrajectoryGeneration totg(params.path_tolerance, params.resample_dt, params.min_angle_change);
if (!totg.computeTimeStamps(*res.trajectory, req.max_velocity_scaling_factor, req.max_acceleration_scaling_factor))
{
RCLCPP_WARN(LOGGER, " Time parametrization for the solution path failed.");
Expand All @@ -84,9 +82,7 @@ class AddTimeOptimalParameterization : public planning_request_adapter::Planning
}

protected:
double path_tolerance_;
double resample_dt_;
double min_angle_change_;
std::shared_ptr<default_plan_request_adapter_parameters::ParamListener> param_listener_;
};

} // namespace default_planner_request_adapters
Expand Down