Skip to content

Commit

Permalink
Implements a collision clearance cost based on distance checks
Browse files Browse the repository at this point in the history
  • Loading branch information
henningkayser committed Jan 31, 2024
1 parent 3d16b4a commit e312201
Show file tree
Hide file tree
Showing 4 changed files with 62 additions and 6 deletions.
43 changes: 43 additions & 0 deletions moveit_planners/stomp/include/stomp_moveit/cost_functions.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -215,6 +215,49 @@ CostFn getCollisionCostFunction(const std::shared_ptr<const planning_scene::Plan
return getCostFunctionFromStateValidator(collision_validator_fn, COL_CHECK_DISTANCE);
}

/**
* Creates a cost function for distances to collisions of group states in the planning scene.
*
* @param planning_scene The planning scene instance to use for distance checking
* @param group The group to use for computing link transforms from joint positions
*
* @return Cost function that computes smooth costs for close-to-collision path segments
*/
CostFn getCollisionDistanceCostFunction(const std::shared_ptr<const planning_scene::PlanningScene>& planning_scene,
const moveit::core::JointModelGroup* group, double min_distance = 0.03)
{
const auto& joints = group ? group->getActiveJointModels() : planning_scene->getRobotModel()->getActiveJointModels();

StateValidatorFn distance_check_fn = [=](const Eigen::VectorXd& positions) {
static moveit::core::RobotState state(planning_scene->getCurrentState());

// Update robot state values
setJointPositions(positions, joints, state);
state.update();

// NOTE: if we need support for filtering links or attached objects, we can do this using DistanceRequests
return min_distance - planning_scene->distanceToCollisionUnpadded(state);
};

CostFn cost_fn = [=](const Eigen::MatrixXd& values, Eigen::VectorXd& costs, bool& validity) {
// Assume zero cost and valid trajectory from the start
costs.setZero(values.cols());
validity = true;

// Iterate over sample waypoints and check for collision distances
for (int timestep = 0; timestep < values.cols(); ++timestep)
{
Eigen::VectorXd current = values.col(timestep);
costs(timestep) += distance_check_fn(current);
validity = validity && costs(timestep) <= 0.0;
}

return true;
};

return cost_fn;
}

/**
* Creates a cost function for binary constraint checks applied to group states.
* This function uses a StateValidatorFn for computing smooth penalty costs from binary
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,8 @@ class StompPlanningContext : public planning_interface::PlanningContext
void setPathPublisher(const std::shared_ptr<rclcpp::Publisher<visualization_msgs::msg::MarkerArray>>& path_publisher);
std::shared_ptr<rclcpp::Publisher<visualization_msgs::msg::MarkerArray>> getPathPublisher();

const stomp_moveit::Params& getParams() const;

private:
const stomp_moveit::Params params_;
std::shared_ptr<stomp::Stomp> stomp_;
Expand Down
5 changes: 5 additions & 0 deletions moveit_planners/stomp/res/stomp_moveit.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,11 @@ stomp_moveit:
description: "Weight of the acceleration costs to be applied for the general cost calculation. A value of 0 disables this cost.",
default_value: 0.1,
}
maximize_clearance: {
type: bool,
description: "Experimental: Enables a cost function that attempts to maximize the distance to collision.",
default_value: false,
}
delta_t: {
type: double,
description: "Assumed time change between consecutive points - used for computing control costs",
Expand Down
18 changes: 12 additions & 6 deletions moveit_planners/stomp/src/stomp_moveit_planning_context.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -159,21 +159,22 @@ stomp::TaskPtr createStompTask(const stomp::StompConfiguration& config, StompPla
// Cost, noise and filter functions are provided for planning.
// TODO(henningkayser): parameterize cost penalties
using namespace stomp_moveit;
CostFn cost_fn;
std::vector<CostFn> cost_functions = { costs::getCollisionCostFunction(planning_scene, group,
1.0 /* collision penalty */) };
if (!constraints.empty())
{
cost_fn = costs::sum({ costs::getCollisionCostFunction(planning_scene, group, 1.0 /* collision penalty */),
costs::getConstraintsCostFunction(planning_scene, group, constraints.getAllConstraints(),
1.0 /* constraint penalty */) });
cost_functions.push_back(costs::getConstraintsCostFunction(planning_scene, group, constraints.getAllConstraints(),
1.0 /* constraint penalty */));
}
else
if (context.getParams().maximize_clearance)
{
cost_fn = costs::getCollisionCostFunction(planning_scene, group, 1.0 /* collision penalty */);
cost_functions.push_back(costs::getCollisionDistanceCostFunction(planning_scene, group));
}

// TODO(henningkayser): parameterize stddev
const std::vector<double> stddev(group->getActiveJointModels().size(), 0.1);
auto noise_generator_fn = noise::getNormalDistributionGenerator(num_timesteps, stddev);
auto cost_fn = costs::sum(cost_functions);
auto filter_fn =
filters::chain({ filters::simpleSmoothingMatrix(num_timesteps), filters::enforcePositionBounds(group) });
auto iteration_callback_fn =
Expand Down Expand Up @@ -301,6 +302,11 @@ void StompPlanningContext::clear()
{
}

const stomp_moveit::Params& StompPlanningContext::getParams() const
{
return params_;
}

void StompPlanningContext::setPathPublisher(
const std::shared_ptr<rclcpp::Publisher<visualization_msgs::msg::MarkerArray>>& path_publisher)
{
Expand Down

0 comments on commit e312201

Please sign in to comment.