Skip to content

Commit 42a08d6

Browse files
committed
PassThrough: cleanup unused headers
1 parent a84479c commit 42a08d6

File tree

2 files changed

+0
-17
lines changed

2 files changed

+0
-17
lines changed

core/include/moveit/task_constructor/stages/passthrough.h

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -36,9 +36,6 @@
3636
#pragma once
3737

3838
#include <moveit/task_constructor/container.h>
39-
#include <moveit/task_constructor/cost_queue.h>
40-
#include <geometry_msgs/PoseStamped.h>
41-
#include <Eigen/Geometry>
4239

4340
namespace moveit {
4441
namespace task_constructor {

core/src/stages/passthrough.cpp

Lines changed: 0 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -34,20 +34,6 @@
3434
/* Author: Michael 'v4hn' Goerner */
3535

3636
#include <moveit/task_constructor/stages/passthrough.h>
37-
#include <moveit/task_constructor/storage.h>
38-
#include <moveit/task_constructor/marker_tools.h>
39-
40-
#include <moveit/task_constructor/container_p.h>
41-
42-
#include <moveit/planning_scene/planning_scene.h>
43-
#include <moveit/robot_state/conversions.h>
44-
#include <moveit/robot_state/robot_state.h>
45-
46-
#include <Eigen/Geometry>
47-
#include <chrono>
48-
#include <functional>
49-
#include <iterator>
50-
#include <ros/console.h>
5137

5238
namespace moveit {
5339
namespace task_constructor {

0 commit comments

Comments
 (0)