Skip to content

Commit feb6e27

Browse files
CihatAltiparmakmarioprats
authored andcommitted
Use .hpp headers (moveit#641)
based on PR moveit/moveit2#3113
1 parent dd7ebbf commit feb6e27

File tree

86 files changed

+213
-142
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

86 files changed

+213
-142
lines changed

.clang-tidy

-1
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,6 @@ Checks: 'performance-*,
1717
readability-identifier-naming,
1818
'
1919
HeaderFilterRegex: '.*/moveit/task_constructor/.*\.h'
20-
AnalyzeTemporaryDtors: false
2120
CheckOptions:
2221
- key: llvm-namespace-comment.ShortNamespaceLines
2322
value: '10'

capabilities/src/execute_task_solution_capability.cpp

+9-8
Original file line numberDiff line numberDiff line change
@@ -36,14 +36,15 @@
3636

3737
#include "execute_task_solution_capability.h"
3838

39-
#include <moveit/moveit_cpp/moveit_cpp.h>
40-
#include <moveit/plan_execution/plan_execution.h>
41-
#include <moveit/trajectory_processing/trajectory_tools.h>
42-
#include <moveit/kinematic_constraints/utils.h>
43-
#include <moveit/move_group/capability_names.h>
44-
#include <moveit/robot_state/conversions.h>
45-
#include <moveit/utils/message_checks.h>
46-
#include <moveit/moveit_cpp/moveit_cpp.h>
39+
#include <moveit/moveit_cpp/moveit_cpp.hpp>
40+
#include <moveit/plan_execution/plan_execution.hpp>
41+
#include <moveit/trajectory_processing/trajectory_tools.hpp>
42+
#include <moveit/kinematic_constraints/utils.hpp>
43+
#include <moveit/move_group/capability_names.hpp>
44+
#include <moveit/robot_state/conversions.hpp>
45+
#include <moveit/utils/message_checks.hpp>
46+
#include <moveit/moveit_cpp/moveit_cpp.hpp>
47+
#include <fmt/format.h>
4748

4849
#include <boost/algorithm/string/join.hpp>
4950

capabilities/src/execute_task_solution_capability.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,7 @@
4141

4242
#pragma once
4343

44-
#include <moveit/move_group/move_group_capability.h>
44+
#include <moveit/move_group/move_group_capability.hpp>
4545
#include <rclcpp_action/rclcpp_action.hpp>
4646

4747
#include <moveit_task_constructor_msgs/action/execute_task_solution.hpp>

core/include/moveit/task_constructor/container_p.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@
3939
#pragma once
4040

4141
#include <moveit/task_constructor/container.h>
42-
#include <moveit/macros/class_forward.h>
42+
#include <moveit/macros/class_forward.hpp>
4343
#include "stage_p.h"
4444

4545
#include <boost/bimap.hpp>

core/include/moveit/task_constructor/introspection.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,7 @@
3838

3939
#pragma once
4040

41-
#include <moveit/macros/class_forward.h>
41+
#include <moveit/macros/class_forward.hpp>
4242
#include <moveit_task_constructor_msgs/msg/task_description.hpp>
4343
#include <moveit_task_constructor_msgs/msg/task_statistics.hpp>
4444
#include <moveit_task_constructor_msgs/msg/solution.hpp>

core/include/moveit/task_constructor/marker_tools.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22

33
#include <rviz_marker_tools/marker_creation.h>
44
#include <visualization_msgs/msg/marker.hpp>
5-
#include <moveit/macros/class_forward.h>
5+
#include <moveit/macros/class_forward.hpp>
66
#include <functional>
77

88
namespace planning_scene {

core/include/moveit/task_constructor/merge.h

+3-3
Original file line numberDiff line numberDiff line change
@@ -37,9 +37,9 @@
3737
#pragma once
3838

3939
#include <moveit/task_constructor/storage.h>
40-
#include <moveit/robot_model/robot_model.h>
41-
#include <moveit/robot_trajectory/robot_trajectory.h>
42-
#include <moveit/trajectory_processing/time_parameterization.h>
40+
#include <moveit/robot_model/robot_model.hpp>
41+
#include <moveit/robot_trajectory/robot_trajectory.hpp>
42+
#include <moveit/trajectory_processing/time_parameterization.hpp>
4343

4444
namespace moveit {
4545
namespace task_constructor {

core/include/moveit/task_constructor/moveit_compat.h

+2-2
Original file line numberDiff line numberDiff line change
@@ -38,8 +38,8 @@
3838

3939
#pragma once
4040

41-
#include <moveit/version.h>
42-
#include <moveit/macros/class_forward.h>
41+
#include <moveit/version.hpp>
42+
#include <moveit/macros/class_forward.hpp>
4343

4444
#define MOVEIT_VERSION_GE(major, minor, patch) \
4545
(MOVEIT_VERSION_MAJOR * 1'000'000 + MOVEIT_VERSION_MINOR * 1'000 + MOVEIT_VERSION_PATCH >= \

core/include/moveit/task_constructor/solvers/joint_interpolation.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@
3939
#pragma once
4040

4141
#include <moveit/task_constructor/solvers/planner_interface.h>
42-
#include <moveit/macros/class_forward.h>
42+
#include <moveit/macros/class_forward.hpp>
4343

4444
namespace moveit {
4545
namespace task_constructor {

core/include/moveit/task_constructor/solvers/pipeline_planner.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@
4343
#include <moveit/planning_pipeline_interfaces/solution_selection_functions.hpp>
4444
#include <moveit/planning_pipeline_interfaces/stopping_criterion_functions.hpp>
4545
#include <rclcpp/node.hpp>
46-
#include <moveit/macros/class_forward.h>
46+
#include <moveit/macros/class_forward.hpp>
4747

4848
namespace planning_pipeline {
4949
MOVEIT_CLASS_FORWARD(PlanningPipeline);

core/include/moveit/task_constructor/solvers/planner_interface.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,7 @@
3838

3939
#pragma once
4040

41-
#include <moveit/macros/class_forward.h>
41+
#include <moveit/macros/class_forward.hpp>
4242
#include <moveit_msgs/msg/constraints.hpp>
4343
#include <moveit/task_constructor/properties.h>
4444
#include <Eigen/Geometry>

core/include/moveit/task_constructor/stage.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,7 @@
4141

4242
#include "trajectory_execution_info.h"
4343
#include "utils.h"
44-
#include <moveit/macros/class_forward.h>
44+
#include <moveit/macros/class_forward.hpp>
4545
#include <moveit/task_constructor/storage.h>
4646
#include <vector>
4747
#include <list>

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

+1-1
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,7 @@
4141
#include <moveit/task_constructor/storage.h>
4242
#include <moveit/task_constructor/stage.h>
4343
#include <geometry_msgs/msg/vector3.hpp>
44-
#include <moveit/collision_detection/collision_common.h>
44+
#include <moveit/collision_detection/collision_common.hpp>
4545

4646
namespace moveit {
4747
namespace task_constructor {
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,64 @@
1+
/*********************************************************************
2+
* Software License Agreement (BSD License)
3+
*
4+
* Copyright (c) 2024, Sherbrooke University
5+
* All rights reserved.
6+
*
7+
* Redistribution and use in source and binary forms, with or without
8+
* modification, are permitted provided that the following conditions
9+
* are met:
10+
*
11+
* * Redistributions of source code must retain the above copyright
12+
* notice, this list of conditions and the following disclaimer.
13+
* * Redistributions in binary form must reproduce the above
14+
* copyright notice, this list of conditions and the following
15+
* disclaimer in the documentation and/or other materials provided
16+
* with the distribution.
17+
* * Neither the name of Bielefeld University nor the names of its
18+
* contributors may be used to endorse or promote products derived
19+
* from this software without specific prior written permission.
20+
*
21+
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22+
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23+
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24+
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25+
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26+
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27+
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28+
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29+
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30+
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31+
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32+
* POSSIBILITY OF SUCH DAMAGE.
33+
*********************************************************************/
34+
/* Authors: Captain Yoshi */
35+
36+
#pragma once
37+
38+
#include <moveit/task_constructor/stage.h>
39+
#include <moveit/planning_scene/planning_scene.hpp>
40+
41+
namespace moveit {
42+
namespace task_constructor {
43+
namespace stages {
44+
45+
/** no-op stage, which doesn't modify the interface state nor adds a trajectory.
46+
* However, it can be used to store custom stage properties,
47+
* which in turn can be queried post-planning to steer the execution.
48+
*/
49+
50+
class NoOp : public PropagatingEitherWay
51+
{
52+
public:
53+
NoOp(const std::string& name = "no-op") : PropagatingEitherWay(name){};
54+
55+
private:
56+
bool compute(const InterfaceState& state, planning_scene::PlanningScenePtr& scene, SubTrajectory& /*trajectory*/,
57+
Interface::Direction /*dir*/) override {
58+
scene = state.scene()->diff();
59+
return true;
60+
};
61+
};
62+
} // namespace stages
63+
} // namespace task_constructor
64+
} // namespace moveit

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

+1-1
Original file line numberDiff line numberDiff line change
@@ -36,7 +36,7 @@
3636

3737
#pragma once
3838

39-
#include <moveit/macros/class_forward.h>
39+
#include <moveit/macros/class_forward.hpp>
4040
#include <moveit/task_constructor/container.h>
4141
#include <geometry_msgs/msg/twist_stamped.hpp>
4242

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

+1-1
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,7 @@
3737
#pragma once
3838

3939
#include <moveit/task_constructor/container.h>
40-
#include <moveit/macros/class_forward.h>
40+
#include <moveit/macros/class_forward.hpp>
4141
#include <geometry_msgs/msg/pose_stamped.hpp>
4242
#include <Eigen/Geometry>
4343

core/include/moveit/task_constructor/storage.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@
3939

4040
#pragma once
4141

42-
#include <moveit/macros/class_forward.h>
42+
#include <moveit/macros/class_forward.hpp>
4343
#include <moveit/task_constructor/properties.h>
4444
#include <moveit/task_constructor/cost_queue.h>
4545
#include <moveit_task_constructor_msgs/msg/solution.hpp>

core/include/moveit/task_constructor/task.h

+2-2
Original file line numberDiff line numberDiff line change
@@ -44,10 +44,10 @@
4444
#include <moveit/task_constructor/introspection.h>
4545
#include <moveit_task_constructor_msgs/msg/solution.hpp>
4646

47-
#include <moveit/macros/class_forward.h>
47+
#include <moveit/macros/class_forward.hpp>
4848

4949
#include <moveit_msgs/msg/move_it_error_codes.hpp>
50-
#include <moveit/utils/moveit_error_code.h>
50+
#include <moveit/utils/moveit_error_code.hpp>
5151

5252
#include <rclcpp/node.hpp>
5353

core/include/moveit/task_constructor/utils.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,7 @@
4444

4545
#include <Eigen/Geometry>
4646

47-
#include <moveit/macros/class_forward.h>
47+
#include <moveit/macros/class_forward.hpp>
4848

4949
namespace planning_scene {
5050
MOVEIT_CLASS_FORWARD(PlanningScene);

core/python/bindings/src/core.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -39,9 +39,9 @@
3939
#include <moveit/task_constructor/container_p.h>
4040
#include <moveit/task_constructor/task.h>
4141

42-
#include <moveit/planning_scene/planning_scene.h>
43-
#include <moveit/planning_scene_interface/planning_scene_interface.h>
44-
#include <moveit/move_group_interface/move_group_interface.h>
42+
#include <moveit/planning_scene/planning_scene.hpp>
43+
#include <moveit/planning_scene_interface/planning_scene_interface.hpp>
44+
#include <moveit/move_group_interface/move_group_interface.hpp>
4545

4646
namespace py = pybind11;
4747
using namespace py::literals;

core/python/bindings/src/core.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,7 @@
3838
#include <moveit/task_constructor/container.h>
3939
#include <moveit/task_constructor/cost_queue.h>
4040
#include <moveit/task_constructor/cost_terms.h>
41-
#include <moveit/utils/moveit_error_code.h>
41+
#include <moveit/utils/moveit_error_code.hpp>
4242
#include <pybind11/smart_holder.h>
4343

4444
/** Trampoline classes to allow inheritance in Python (overriding virtual functions) */

core/python/bindings/src/stages.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -37,8 +37,8 @@
3737
#include <moveit/task_constructor/stages.h>
3838
#include <moveit/task_constructor/stages/pick.h>
3939
#include <moveit/task_constructor/stages/simple_grasp.h>
40-
#include <moveit/planning_scene/planning_scene.h>
41-
#include <moveit_msgs/PlanningScene.h>
40+
#include <moveit/planning_scene/planning_scene.hpp>
41+
#include <moveit_msgs/msg/planning_scene.hpp>
4242
#include <pybind11/stl.h>
4343
#include <moveit/python/pybind_rosmsg_typecasters.h>
4444

core/src/container.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -37,8 +37,8 @@
3737
#include <moveit/task_constructor/container_p.h>
3838
#include <moveit/task_constructor/introspection.h>
3939
#include <moveit/task_constructor/merge.h>
40-
#include <moveit/planning_scene/planning_scene.h>
41-
#include <moveit/trajectory_processing/time_optimal_trajectory_generation.h>
40+
#include <moveit/planning_scene/planning_scene.hpp>
41+
#include <moveit/trajectory_processing/time_optimal_trajectory_generation.hpp>
4242

4343
#include <rclcpp/logger.hpp>
4444
#include <rclcpp/logging.hpp>

core/src/cost_terms.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -37,10 +37,10 @@
3737
#include <moveit/task_constructor/cost_terms.h>
3838
#include <moveit/task_constructor/stage.h>
3939

40-
#include <moveit/collision_detection/collision_common.h>
41-
#include <moveit/robot_trajectory/robot_trajectory.h>
42-
#include <moveit/planning_scene/planning_scene.h>
43-
#include <moveit/robot_state/conversions.h>
40+
#include <moveit/collision_detection/collision_common.hpp>
41+
#include <moveit/robot_trajectory/robot_trajectory.hpp>
42+
#include <moveit/planning_scene/planning_scene.hpp>
43+
#include <moveit/robot_state/conversions.hpp>
4444

4545
#include <Eigen/Geometry>
4646

core/src/introspection.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,7 @@
4444
#include <rclcpp/node.hpp>
4545
#include <rclcpp/publisher.hpp>
4646
#include <rclcpp/service.hpp>
47-
#include <moveit/planning_scene/planning_scene.h>
47+
#include <moveit/planning_scene/planning_scene.hpp>
4848

4949
#include <sstream>
5050
#include <boost/bimap.hpp>

core/src/marker_tools.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
#include <moveit/task_constructor/marker_tools.h>
2-
#include <moveit/planning_scene/planning_scene.h>
3-
#include <moveit/robot_state/robot_state.h>
2+
#include <moveit/planning_scene/planning_scene.hpp>
3+
#include <moveit/robot_state/robot_state.hpp>
44

55
namespace vm = visualization_msgs;
66

core/src/solvers/cartesian_path.cpp

+10-4
Original file line numberDiff line numberDiff line change
@@ -37,10 +37,16 @@
3737
*/
3838

3939
#include <moveit/task_constructor/solvers/cartesian_path.h>
40-
#include <moveit/planning_scene/planning_scene.h>
41-
#include <moveit/trajectory_processing/time_parameterization.h>
42-
#include <moveit/kinematics_base/kinematics_base.h>
43-
#include <moveit/robot_state/cartesian_interpolator.h>
40+
#include <moveit/task_constructor/utils.h>
41+
#include <moveit/planning_scene/planning_scene.hpp>
42+
#include <moveit/trajectory_processing/time_parameterization.hpp>
43+
#include <moveit/kinematics_base/kinematics_base.hpp>
44+
#include <moveit/robot_state/cartesian_interpolator.hpp>
45+
#if __has_include(<tf2_eigen/tf2_eigen.hpp>)
46+
#include <tf2_eigen/tf2_eigen.hpp>
47+
#else
48+
#include <tf2_eigen/tf2_eigen.h>
49+
#endif
4450

4551
using namespace trajectory_processing;
4652

core/src/solvers/joint_interpolation.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -37,8 +37,8 @@
3737
*/
3838

3939
#include <moveit/task_constructor/solvers/joint_interpolation.h>
40-
#include <moveit/planning_scene/planning_scene.h>
41-
#include <moveit/trajectory_processing/time_parameterization.h>
40+
#include <moveit/planning_scene/planning_scene.hpp>
41+
#include <moveit/trajectory_processing/time_parameterization.hpp>
4242

4343
#include <chrono>
4444

core/src/solvers/multi_planner.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,7 @@
3737
*/
3838

3939
#include <moveit/task_constructor/solvers/multi_planner.h>
40-
#include <moveit/robot_trajectory/robot_trajectory.h>
40+
#include <moveit/robot_trajectory/robot_trajectory.hpp>
4141
#include <chrono>
4242

4343
namespace moveit {

core/src/solvers/pipeline_planner.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -38,10 +38,10 @@
3838

3939
#include <moveit/task_constructor/solvers/pipeline_planner.h>
4040
#include <moveit/task_constructor/task.h>
41-
#include <moveit/planning_scene/planning_scene.h>
42-
#include <moveit/planning_pipeline/planning_pipeline.h>
41+
#include <moveit/planning_scene/planning_scene.hpp>
42+
#include <moveit/planning_pipeline/planning_pipeline.hpp>
4343
#include <moveit_msgs/msg/motion_plan_request.hpp>
44-
#include <moveit/kinematic_constraints/utils.h>
44+
#include <moveit/kinematic_constraints/utils.hpp>
4545

4646
#if __has_include(<tf2_eigen/tf2_eigen.hpp>)
4747
#include <tf2_eigen/tf2_eigen.hpp>

core/src/solvers/planner_interface.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,7 @@
3737
*/
3838

3939
#include <moveit/task_constructor/solvers/planner_interface.h>
40-
#include <moveit/trajectory_processing/time_optimal_trajectory_generation.h>
40+
#include <moveit/trajectory_processing/time_optimal_trajectory_generation.hpp>
4141

4242
using namespace trajectory_processing;
4343

0 commit comments

Comments
 (0)