diff --git a/doc/how_to_guides/planner_cost_functions/src/planner_cost_functions_main.cpp b/doc/how_to_guides/planner_cost_functions/src/planner_cost_functions_main.cpp index f6a9b54619..c690be291a 100644 --- a/doc/how_to_guides/planner_cost_functions/src/planner_cost_functions_main.cpp +++ b/doc/how_to_guides/planner_cost_functions/src/planner_cost_functions_main.cpp @@ -264,7 +264,7 @@ class Demo planning_component_->setStateCostFunction( [robot_start_state, group_name, planning_scene](const Eigen::VectorXd& state_vector) mutable { auto clearance_cost_fn = - moveit::cost_functions::getMinJointDisplacementCostFn(*robot_start_state, group_name, planning_scene); + moveit::cost_functions::createMinJointDisplacementCostFn(*robot_start_state, group_name, planning_scene); return clearance_cost_fn(state_vector); }); }