Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Enhancement/use hpp for headers based on PR https://github.com/moveit/moveit2/pull/3113 #641

Merged
merged 2 commits into from
Dec 22, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 0 additions & 1 deletion .clang-tidy
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@ Checks: 'performance-*,
readability-identifier-naming,
'
HeaderFilterRegex: '.*/moveit/task_constructor/.*\.h'
AnalyzeTemporaryDtors: false
CheckOptions:
- key: llvm-namespace-comment.ShortNamespaceLines
value: '10'
Expand Down
14 changes: 7 additions & 7 deletions capabilities/src/execute_task_solution_capability.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,13 +36,13 @@

#include "execute_task_solution_capability.h"

#include <moveit/moveit_cpp/moveit_cpp.h>
#include <moveit/plan_execution/plan_execution.h>
#include <moveit/trajectory_processing/trajectory_tools.h>
#include <moveit/kinematic_constraints/utils.h>
#include <moveit/move_group/capability_names.h>
#include <moveit/robot_state/conversions.h>
#include <moveit/utils/message_checks.h>
#include <moveit/moveit_cpp/moveit_cpp.hpp>
#include <moveit/plan_execution/plan_execution.hpp>
#include <moveit/trajectory_processing/trajectory_tools.hpp>
#include <moveit/kinematic_constraints/utils.hpp>
#include <moveit/move_group/capability_names.hpp>
#include <moveit/robot_state/conversions.hpp>
#include <moveit/utils/message_checks.hpp>
#include <fmt/format.h>

namespace {
Expand Down
2 changes: 1 addition & 1 deletion capabilities/src/execute_task_solution_capability.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@

#pragma once

#include <moveit/move_group/move_group_capability.h>
#include <moveit/move_group/move_group_capability.hpp>
#include <rclcpp_action/rclcpp_action.hpp>

#include <moveit_task_constructor_msgs/action/execute_task_solution.hpp>
Expand Down
2 changes: 1 addition & 1 deletion core/include/moveit/task_constructor/container_p.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@
#pragma once

#include <moveit/task_constructor/container.h>
#include <moveit/macros/class_forward.h>
#include <moveit/macros/class_forward.hpp>
#include "stage_p.h"

#include <boost/bimap.hpp>
Expand Down
2 changes: 1 addition & 1 deletion core/include/moveit/task_constructor/introspection.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@

#pragma once

#include <moveit/macros/class_forward.h>
#include <moveit/macros/class_forward.hpp>
#include <moveit_task_constructor_msgs/msg/task_description.hpp>
#include <moveit_task_constructor_msgs/msg/task_statistics.hpp>
#include <moveit_task_constructor_msgs/msg/solution.hpp>
Expand Down
2 changes: 1 addition & 1 deletion core/include/moveit/task_constructor/marker_tools.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

#include <rviz_marker_tools/marker_creation.h>
#include <visualization_msgs/msg/marker.hpp>
#include <moveit/macros/class_forward.h>
#include <moveit/macros/class_forward.hpp>
#include <functional>

namespace planning_scene {
Expand Down
6 changes: 3 additions & 3 deletions core/include/moveit/task_constructor/merge.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,9 +37,9 @@
#pragma once

#include <moveit/task_constructor/storage.h>
#include <moveit/robot_model/robot_model.h>
#include <moveit/robot_trajectory/robot_trajectory.h>
#include <moveit/trajectory_processing/time_parameterization.h>
#include <moveit/robot_model/robot_model.hpp>
#include <moveit/robot_trajectory/robot_trajectory.hpp>
#include <moveit/trajectory_processing/time_parameterization.hpp>

namespace moveit {
namespace task_constructor {
Expand Down
4 changes: 2 additions & 2 deletions core/include/moveit/task_constructor/moveit_compat.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,8 @@

#pragma once

#include <moveit/version.h>
#include <moveit/macros/class_forward.h>
#include <moveit/version.hpp>
#include <moveit/macros/class_forward.hpp>

#define MOVEIT_VERSION_GE(major, minor, patch) \
(MOVEIT_VERSION_MAJOR * 1'000'000 + MOVEIT_VERSION_MINOR * 1'000 + MOVEIT_VERSION_PATCH >= \
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@
#pragma once

#include <moveit/task_constructor/solvers/planner_interface.h>
#include <moveit/robot_state/cartesian_interpolator.h>
#include <moveit/robot_state/cartesian_interpolator.hpp>

namespace moveit {
namespace task_constructor {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@
#pragma once

#include <moveit/task_constructor/solvers/planner_interface.h>
#include <moveit/macros/class_forward.h>
#include <moveit/macros/class_forward.hpp>

namespace moveit {
namespace task_constructor {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@
#include <moveit/planning_pipeline_interfaces/solution_selection_functions.hpp>
#include <moveit/planning_pipeline_interfaces/stopping_criterion_functions.hpp>
#include <rclcpp/node.hpp>
#include <moveit/macros/class_forward.h>
#include <moveit/macros/class_forward.hpp>

namespace planning_pipeline {
MOVEIT_CLASS_FORWARD(PlanningPipeline);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@

#pragma once

#include <moveit/macros/class_forward.h>
#include <moveit/macros/class_forward.hpp>
#include <moveit_msgs/msg/constraints.hpp>
#include <moveit/task_constructor/properties.h>
#include <Eigen/Geometry>
Expand Down
2 changes: 1 addition & 1 deletion core/include/moveit/task_constructor/stage.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@

#include "trajectory_execution_info.h"
#include "utils.h"
#include <moveit/macros/class_forward.h>
#include <moveit/macros/class_forward.hpp>
#include <moveit/task_constructor/storage.h>
#include <vector>
#include <list>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@
#include <moveit/task_constructor/storage.h>
#include <moveit/task_constructor/stage.h>
#include <geometry_msgs/msg/vector3.hpp>
#include <moveit/collision_detection/collision_common.h>
#include <moveit/collision_detection/collision_common.hpp>

namespace moveit {
namespace task_constructor {
Expand Down
2 changes: 1 addition & 1 deletion core/include/moveit/task_constructor/stages/noop.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@
#pragma once

#include <moveit/task_constructor/stage.h>
#include <moveit/planning_scene/planning_scene.h>
#include <moveit/planning_scene/planning_scene.hpp>

namespace moveit {
namespace task_constructor {
Expand Down
2 changes: 1 addition & 1 deletion core/include/moveit/task_constructor/stages/pick.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@

#pragma once

#include <moveit/macros/class_forward.h>
#include <moveit/macros/class_forward.hpp>
#include <moveit/task_constructor/container.h>
#include <geometry_msgs/msg/twist_stamped.hpp>

Expand Down
2 changes: 1 addition & 1 deletion core/include/moveit/task_constructor/stages/simple_grasp.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@
#pragma once

#include <moveit/task_constructor/container.h>
#include <moveit/macros/class_forward.h>
#include <moveit/macros/class_forward.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <Eigen/Geometry>

Expand Down
2 changes: 1 addition & 1 deletion core/include/moveit/task_constructor/storage.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@

#pragma once

#include <moveit/macros/class_forward.h>
#include <moveit/macros/class_forward.hpp>
#include <moveit/task_constructor/properties.h>
#include <moveit/task_constructor/cost_queue.h>
#include <moveit_task_constructor_msgs/msg/solution.hpp>
Expand Down
4 changes: 2 additions & 2 deletions core/include/moveit/task_constructor/task.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,10 +44,10 @@
#include <moveit/task_constructor/introspection.h>
#include <moveit_task_constructor_msgs/msg/solution.hpp>

#include <moveit/macros/class_forward.h>
#include <moveit/macros/class_forward.hpp>

#include <moveit_msgs/msg/move_it_error_codes.hpp>
#include <moveit/utils/moveit_error_code.h>
#include <moveit/utils/moveit_error_code.hpp>

#include <rclcpp/node.hpp>

Expand Down
2 changes: 1 addition & 1 deletion core/include/moveit/task_constructor/utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@

#include <Eigen/Geometry>

#include <moveit/macros/class_forward.h>
#include <moveit/macros/class_forward.hpp>

namespace planning_scene {
MOVEIT_CLASS_FORWARD(PlanningScene);
Expand Down
6 changes: 3 additions & 3 deletions core/python/bindings/src/core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,9 +40,9 @@
#include <moveit/task_constructor/container_p.h>
#include <moveit/task_constructor/task.h>

#include <moveit/planning_scene/planning_scene.h>
#include <moveit/planning_scene_interface/planning_scene_interface.h>
#include <moveit/move_group_interface/move_group_interface.h>
#include <moveit/planning_scene/planning_scene.hpp>
#include <moveit/planning_scene_interface/planning_scene_interface.hpp>
#include <moveit/move_group_interface/move_group_interface.hpp>

namespace py = pybind11;
using namespace py::literals;
Expand Down
2 changes: 1 addition & 1 deletion core/python/bindings/src/core.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@
#include <moveit/task_constructor/container.h>
#include <moveit/task_constructor/cost_queue.h>
#include <moveit/task_constructor/cost_terms.h>
#include <moveit/utils/moveit_error_code.h>
#include <moveit/utils/moveit_error_code.hpp>
#include <pybind11/smart_holder.h>

/** Trampoline classes to allow inheritance in Python (overriding virtual functions) */
Expand Down
2 changes: 1 addition & 1 deletion core/python/bindings/src/stages.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@
#include <moveit/task_constructor/stages.h>
#include <moveit/task_constructor/stages/pick.h>
#include <moveit/task_constructor/stages/simple_grasp.h>
#include <moveit/planning_scene/planning_scene.h>
#include <moveit/planning_scene/planning_scene.hpp>
#include <moveit_msgs/msg/planning_scene.hpp>
#include <pybind11/stl.h>
#include <py_binding_tools/ros_msg_typecasters.h>
Expand Down
4 changes: 2 additions & 2 deletions core/src/container.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,8 @@
#include <moveit/task_constructor/introspection.h>
#include <moveit/task_constructor/merge.h>
#include <moveit/task_constructor/fmt_p.h>
#include <moveit/planning_scene/planning_scene.h>
#include <moveit/trajectory_processing/time_optimal_trajectory_generation.h>
#include <moveit/planning_scene/planning_scene.hpp>
#include <moveit/trajectory_processing/time_optimal_trajectory_generation.hpp>

#include <rclcpp/logger.hpp>
#include <rclcpp/logging.hpp>
Expand All @@ -63,24 +63,24 @@
std::ostream& os = std::cerr) {
static unsigned int id = 0;
const unsigned int width = 10; // indentation of name
os << std::endl << (success ? '+' : '-') << ' ' << creator.name() << ' ';

Check failure on line 66 in core/src/container.cpp

View workflow job for this annotation

GitHub Actions / rolling-source • clang-tidy

clang-tidy: do not use 'std::endl' with streams; use '\n' instead (performance-avoid-endl)
if (success)
os << ++id << ' ';
if (const auto conn = dynamic_cast<const ConnectingPrivate*>(creator.pimpl()))
os << conn->pendingPairsPrinter();
os << std::endl;

Check failure on line 71 in core/src/container.cpp

View workflow job for this annotation

GitHub Actions / rolling-source • clang-tidy

clang-tidy: do not use 'std::endl' with streams; use '\n' instead (performance-avoid-endl)

for (const auto& child : container.children()) {
auto cimpl = child->pimpl();
os << std::setw(width) << std::left << child->name();
if (!cimpl->starts() && !cimpl->ends())
os << "↕ " << std::endl;

Check failure on line 77 in core/src/container.cpp

View workflow job for this annotation

GitHub Actions / rolling-source • clang-tidy

clang-tidy: do not use 'std::endl' with streams; use '\n' instead (performance-avoid-endl)
if (cimpl->starts())
os << "↓ " << *child->pimpl()->starts() << std::endl;

Check failure on line 79 in core/src/container.cpp

View workflow job for this annotation

GitHub Actions / rolling-source • clang-tidy

clang-tidy: do not use 'std::endl' with streams; use '\n' instead (performance-avoid-endl)
if (cimpl->starts() && cimpl->ends())
os << std::setw(width) << " ";
if (cimpl->ends())
os << "↑ " << *child->pimpl()->ends() << std::endl;

Check failure on line 83 in core/src/container.cpp

View workflow job for this annotation

GitHub Actions / rolling-source • clang-tidy

clang-tidy: do not use 'std::endl' with streams; use '\n' instead (performance-avoid-endl)
}
}

Expand Down Expand Up @@ -460,7 +460,7 @@
if (stage->numFailures()) {
os << stage->name() << " (0/" << stage->numFailures() << ")";
stage->explainFailure(os);
os << std::endl;

Check failure on line 463 in core/src/container.cpp

View workflow job for this annotation

GitHub Actions / rolling-source • clang-tidy

clang-tidy: do not use 'std::endl' with streams; use '\n' instead (performance-avoid-endl)
break;
}
stage->explainFailure(os); // recursively process children
Expand All @@ -469,7 +469,7 @@

std::ostream& operator<<(std::ostream& os, const ContainerBase& container) {
ContainerBase::StageCallback processor = [&os](const Stage& stage, unsigned int depth) -> bool {
os << std::string(2 * depth, ' ') << *stage.pimpl() << std::endl;

Check failure on line 472 in core/src/container.cpp

View workflow job for this annotation

GitHub Actions / rolling-source • clang-tidy

clang-tidy: do not use 'std::endl' with streams; use '\n' instead (performance-avoid-endl)
return true;
};
container.traverseRecursively(processor);
Expand Down
8 changes: 4 additions & 4 deletions core/src/cost_terms.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,10 +38,10 @@
#include <moveit/task_constructor/stage.h>
#include <moveit/task_constructor/fmt_p.h>

#include <moveit/collision_detection/collision_common.h>
#include <moveit/robot_trajectory/robot_trajectory.h>
#include <moveit/planning_scene/planning_scene.h>
#include <moveit/robot_state/conversions.h>
#include <moveit/collision_detection/collision_common.hpp>
#include <moveit/robot_trajectory/robot_trajectory.hpp>
#include <moveit/planning_scene/planning_scene.hpp>
#include <moveit/robot_state/conversions.hpp>

#include <Eigen/Geometry>

Expand Down
2 changes: 1 addition & 1 deletion core/src/introspection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@
#include <rclcpp/node.hpp>
#include <rclcpp/publisher.hpp>
#include <rclcpp/service.hpp>
#include <moveit/planning_scene/planning_scene.h>
#include <moveit/planning_scene/planning_scene.hpp>

#include <sstream>
#include <boost/bimap.hpp>
Expand Down Expand Up @@ -206,7 +206,7 @@
publishSolution(*solution);

if (wait) {
std::cout << "Press <Enter> to continue ..." << std::endl;

Check failure on line 209 in core/src/introspection.cpp

View workflow job for this annotation

GitHub Actions / rolling-source • clang-tidy

clang-tidy: do not use 'std::endl' with streams; use '\n' instead (performance-avoid-endl)
int ch = getchar();
if (ch == 'q' || ch == 'Q')
break;
Expand Down
4 changes: 2 additions & 2 deletions core/src/marker_tools.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include <moveit/task_constructor/marker_tools.h>
#include <moveit/planning_scene/planning_scene.h>
#include <moveit/robot_state/robot_state.h>
#include <moveit/planning_scene/planning_scene.hpp>
#include <moveit/robot_state/robot_state.hpp>

namespace vm = visualization_msgs;

Expand Down
8 changes: 4 additions & 4 deletions core/src/solvers/cartesian_path.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,10 +38,10 @@

#include <moveit/task_constructor/solvers/cartesian_path.h>
#include <moveit/task_constructor/utils.h>
#include <moveit/planning_scene/planning_scene.h>
#include <moveit/trajectory_processing/time_parameterization.h>
#include <moveit/kinematics_base/kinematics_base.h>
#include <moveit/robot_state/cartesian_interpolator.h>
#include <moveit/planning_scene/planning_scene.hpp>
#include <moveit/trajectory_processing/time_parameterization.hpp>
#include <moveit/kinematics_base/kinematics_base.hpp>
#include <moveit/robot_state/cartesian_interpolator.hpp>
#if __has_include(<tf2_eigen/tf2_eigen.hpp>)
#include <tf2_eigen/tf2_eigen.hpp>
#else
Expand Down
4 changes: 2 additions & 2 deletions core/src/solvers/joint_interpolation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,8 @@
*/

#include <moveit/task_constructor/solvers/joint_interpolation.h>
#include <moveit/planning_scene/planning_scene.h>
#include <moveit/trajectory_processing/time_parameterization.h>
#include <moveit/planning_scene/planning_scene.hpp>
#include <moveit/trajectory_processing/time_parameterization.hpp>

#include <chrono>

Expand Down
2 changes: 1 addition & 1 deletion core/src/solvers/multi_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@
*/

#include <moveit/task_constructor/solvers/multi_planner.h>
#include <moveit/robot_trajectory/robot_trajectory.h>
#include <moveit/robot_trajectory/robot_trajectory.hpp>
#include <chrono>

namespace moveit {
Expand Down
6 changes: 3 additions & 3 deletions core/src/solvers/pipeline_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,10 +38,10 @@

#include <moveit/task_constructor/solvers/pipeline_planner.h>
#include <moveit/task_constructor/task.h>
#include <moveit/planning_scene/planning_scene.h>
#include <moveit/planning_pipeline/planning_pipeline.h>
#include <moveit/planning_scene/planning_scene.hpp>
#include <moveit/planning_pipeline/planning_pipeline.hpp>
#include <moveit_msgs/msg/motion_plan_request.hpp>
#include <moveit/kinematic_constraints/utils.h>
#include <moveit/kinematic_constraints/utils.hpp>

#if __has_include(<tf2_eigen/tf2_eigen.hpp>)
#include <tf2_eigen/tf2_eigen.hpp>
Expand Down
2 changes: 1 addition & 1 deletion core/src/solvers/planner_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@
*/

#include <moveit/task_constructor/solvers/planner_interface.h>
#include <moveit/trajectory_processing/time_optimal_trajectory_generation.h>
#include <moveit/trajectory_processing/time_optimal_trajectory_generation.hpp>

using namespace trajectory_processing;

Expand Down
2 changes: 1 addition & 1 deletion core/src/stage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@
#include <moveit/task_constructor/introspection.h>
#include <moveit/task_constructor/fmt_p.h>

#include <moveit/planning_scene/planning_scene.h>
#include <moveit/planning_scene/planning_scene.hpp>

#include <rclcpp/logging.hpp>

Expand Down Expand Up @@ -92,9 +92,9 @@

std::ostream& operator<<(std::ostream& os, const InitStageException& e) {
os << "Error initializing stage" << (e.errors_.size() > 1 ? "s" : "") << ":" << std::endl;
for (const auto& pair : e.errors_)

Check failure on line 95 in core/src/stage.cpp

View workflow job for this annotation

GitHub Actions / rolling-source • clang-tidy

clang-tidy: do not use 'std::endl' with streams; use '\n' instead (performance-avoid-endl)
os << pair.first->name() << ": " << pair.second << std::endl;
return os;

Check failure on line 97 in core/src/stage.cpp

View workflow job for this annotation

GitHub Actions / rolling-source • clang-tidy

clang-tidy: do not use 'std::endl' with streams; use '\n' instead (performance-avoid-endl)
}

StagePrivate::StagePrivate(Stage* me, const std::string& name)
Expand Down
6 changes: 3 additions & 3 deletions core/src/stages/compute_ik.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,9 +39,9 @@
#include <moveit/task_constructor/marker_tools.h>
#include <moveit/task_constructor/fmt_p.h>

#include <moveit/planning_scene/planning_scene.h>
#include <moveit/robot_state/conversions.h>
#include <moveit/robot_state/robot_state.h>
#include <moveit/planning_scene/planning_scene.hpp>
#include <moveit/robot_state/conversions.hpp>
#include <moveit/robot_state/robot_state.hpp>

#include <Eigen/Geometry>
#if __has_include(<tf2_eigen/tf2_eigen.hpp>)
Expand Down
4 changes: 2 additions & 2 deletions core/src/stages/connect.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,8 +41,8 @@
#include <moveit/task_constructor/cost_terms.h>
#include <moveit/task_constructor/fmt_p.h>

#include <moveit/planning_scene/planning_scene.h>
#include <moveit/trajectory_processing/time_optimal_trajectory_generation.h>
#include <moveit/planning_scene/planning_scene.hpp>
#include <moveit/trajectory_processing/time_optimal_trajectory_generation.hpp>

#if FMT_VERSION >= 90000
template <>
Expand Down
4 changes: 2 additions & 2 deletions core/src/stages/current_state.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,8 +41,8 @@
#include <moveit/task_constructor/storage.h>
#include <moveit_msgs/srv/get_planning_scene.hpp>
#include <moveit_msgs/msg/planning_scene_components.hpp>
#include <moveit/planning_scene/planning_scene.h>
#include <moveit/robot_model_loader/robot_model_loader.h>
#include <moveit/planning_scene/planning_scene.hpp>
#include <moveit/robot_model_loader/robot_model_loader.hpp>
#include <rclcpp/rclcpp.hpp>

namespace moveit {
Expand Down
2 changes: 1 addition & 1 deletion core/src/stages/fix_collision_objects.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@
#include <moveit/task_constructor/storage.h>
#include <moveit/task_constructor/fmt_p.h>

#include <moveit/planning_scene/planning_scene.h>
#include <moveit/planning_scene/planning_scene.hpp>
#include <moveit/task_constructor/cost_terms.h>

#include <rviz_marker_tools/marker_creation.h>
Expand Down
2 changes: 1 addition & 1 deletion core/src/stages/fixed_cartesian_poses.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@
#include <moveit/task_constructor/cost_terms.h>
#include <moveit/task_constructor/marker_tools.h>

#include <moveit/planning_scene/planning_scene.h>
#include <moveit/planning_scene/planning_scene.hpp>
#include <rviz_marker_tools/marker_creation.h>

namespace moveit {
Expand Down
Loading
Loading