diff --git a/moveit_core/cost_functions/src/cost_functions.cpp b/moveit_core/cost_functions/src/cost_functions.cpp index 13fbcc4113c..55fd0b71ac5 100644 --- a/moveit_core/cost_functions/src/cost_functions.cpp +++ b/moveit_core/cost_functions/src/cost_functions.cpp @@ -45,7 +45,7 @@ createClearanceCostFn(moveit::core::RobotState& robot_state, const std::string& const planning_scene::PlanningSceneConstPtr& planning_scene) { // Create cost function - return [robot_state, group_name, planning_scene](const Eigen::VectorXd& state_vector) mutable { + return [&](const Eigen::VectorXd& state_vector) mutable { assert(state_vector.size() == robot_state.getRobotModel()->getJointModelGroup(group_name)->getActiveVariableCount()); robot_state.setJointGroupActivePositions(group_name, state_vector); auto const shortest_distance_to_collision = planning_scene->distanceToCollision(robot_state); @@ -64,7 +64,7 @@ createClearanceCostFn(moveit::core::RobotState& robot_state, const std::string& createMinJointDisplacementCostFn(moveit::core::RobotState& robot_state, const std::string& group_name, const planning_scene::PlanningSceneConstPtr& planning_scene) { - return [robot_state, group_name, planning_scene](const Eigen::VectorXd& state_vector) mutable { + return [&](const Eigen::VectorXd& state_vector) mutable { assert(state_vector.size() == robot_state.getRobotModel()->getJointModelGroup(group_name)->getActiveVariableCount()); robot_state.setJointGroupActivePositions(group_name, state_vector); const auto& current_state = planning_scene->getCurrentState();