Skip to content

Commit

Permalink
Capture by reference
Browse files Browse the repository at this point in the history
  • Loading branch information
sjahr committed Oct 27, 2023
1 parent 2bfaf1e commit 591bfa1
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions moveit_core/cost_functions/src/cost_functions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand All @@ -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();
Expand Down

0 comments on commit 591bfa1

Please sign in to comment.