Skip to content

Commit 905b78b

Browse files
authored
Merge pull request #10 from PickNikRobotics/pr-remove-untested-changes
Revert some untested changes
2 parents f282f8b + 3f4c599 commit 905b78b

File tree

1 file changed

+3
-5
lines changed

1 file changed

+3
-5
lines changed

capabilities/src/execute_task_solution_capability.cpp

+3-5
Original file line numberDiff line numberDiff line change
@@ -176,12 +176,10 @@ bool ExecuteTaskSolutionCapability::constructMotionPlan(const moveit_task_constr
176176
};
177177

178178
auto make_apply_planning_scene_diff_cb = [this](const std::vector<moveit_msgs::msg::PlanningScene>& scene_diffs) {
179-
return [this,
180-
&scene_diffs = std::as_const(scene_diffs)](const plan_execution::ExecutableMotionPlan* /*plan*/) mutable {
181-
for (auto& const_scene_diff : scene_diffs) {
182-
if (!moveit::core::isEmpty(const_scene_diff)) {
179+
return [this, scene_diffs = scene_diffs](const plan_execution::ExecutableMotionPlan* /*plan*/) mutable {
180+
for (auto& scene_diff : scene_diffs) {
181+
if (!moveit::core::isEmpty(scene_diff)) {
183182
/* RCLCPP_DEBUG_STREAM(LOGGER, "apply effect of " << description); */
184-
moveit_msgs::msg::PlanningScene scene_diff = const_scene_diff;
185183
scene_diff.robot_state.joint_state = sensor_msgs::msg::JointState();
186184
scene_diff.robot_state.multi_dof_joint_state = sensor_msgs::msg::MultiDOFJointState();
187185
if (!context_->planning_scene_monitor_->newPlanningSceneMessage(scene_diff))

0 commit comments

Comments
 (0)