Skip to content

Commit

Permalink
Use .hpp headers (moveit#641)
Browse files Browse the repository at this point in the history
  • Loading branch information
CihatAltiparmak authored and marioprats committed Jan 24, 2025
1 parent dd7ebbf commit feb6e27
Show file tree
Hide file tree
Showing 86 changed files with 213 additions and 142 deletions.
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
17 changes: 9 additions & 8 deletions capabilities/src/execute_task_solution_capability.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,14 +36,15 @@

#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.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 <moveit/moveit_cpp/moveit_cpp.hpp>
#include <fmt/format.h>

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

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/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
64 changes: 64 additions & 0 deletions core/include/moveit/task_constructor/stages/noop.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,64 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2024, Sherbrooke University
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Bielefeld University nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
/* Authors: Captain Yoshi */

#pragma once

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

namespace moveit {
namespace task_constructor {
namespace stages {

/** no-op stage, which doesn't modify the interface state nor adds a trajectory.
* However, it can be used to store custom stage properties,
* which in turn can be queried post-planning to steer the execution.
*/

class NoOp : public PropagatingEitherWay
{
public:
NoOp(const std::string& name = "no-op") : PropagatingEitherWay(name){};

private:
bool compute(const InterfaceState& state, planning_scene::PlanningScenePtr& scene, SubTrajectory& /*trajectory*/,
Interface::Direction /*dir*/) override {
scene = state.scene()->diff();
return true;
};
};
} // namespace stages
} // namespace task_constructor
} // namespace moveit
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 @@ -39,9 +39,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
4 changes: 2 additions & 2 deletions core/python/bindings/src/stages.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,8 @@
#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_msgs/PlanningScene.h>
#include <moveit/planning_scene/planning_scene.hpp>
#include <moveit_msgs/msg/planning_scene.hpp>
#include <pybind11/stl.h>
#include <moveit/python/pybind_rosmsg_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 @@ -37,8 +37,8 @@
#include <moveit/task_constructor/container_p.h>
#include <moveit/task_constructor/introspection.h>
#include <moveit/task_constructor/merge.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 Down
8 changes: 4 additions & 4 deletions core/src/cost_terms.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,10 +37,10 @@
#include <moveit/task_constructor/cost_terms.h>
#include <moveit/task_constructor/stage.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
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
14 changes: 10 additions & 4 deletions core/src/solvers/cartesian_path.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,10 +37,16 @@
*/

#include <moveit/task_constructor/solvers/cartesian_path.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/task_constructor/utils.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
#include <tf2_eigen/tf2_eigen.h>
#endif

using namespace trajectory_processing;

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
Loading

0 comments on commit feb6e27

Please sign in to comment.