From 2c5e59f571408bf903f5dc7016930afffc4c8162 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Sun, 17 Nov 2024 15:39:21 +0000 Subject: [PATCH 01/53] Replaces moveit imports from .h to .hpp --- .../constraint_samplers/test/pr2_arm_ik.cpp | 2 +- .../test/pr2_arm_kinematics_plugin.cpp | 2 +- .../test/pr2_arm_kinematics_plugin.h | 2 +- .../test/test_constraint_samplers.cpp | 2 +- moveit_core/version/CMakeLists.txt | 4 ++-- moveit_core/version/version.cmake | 2 +- .../cached_ik_kinematics_plugin/README.md | 2 +- .../cached_ik_kinematics_plugin.h | 2 +- .../detail/NearestNeighborsGNAT.h | 4 ++-- .../src/cached_ur_kinematics_plugin.cpp | 2 +- .../scripts/create_ikfast_moveit_plugin.py | 6 ++--- .../test_constrained_planning_state_space.cpp | 2 +- .../test/test_ompl_constraints.cpp | 2 +- .../test/test_planning_context_manager.cpp | 2 +- .../test/test_state_validity_checker.cpp | 2 +- .../test/test_threadsafe_state_storage.cpp | 2 +- .../cartesian_trajectory.h | 2 +- .../src/trajectory_generator_lin.cpp | 12 +++++----- .../integrationtest_command_list_manager.cpp | 2 +- .../src/integrationtest_command_planning.cpp | 2 +- .../test/test_utils.cpp | 2 +- ...nittest_pilz_industrial_motion_planner.cpp | 2 +- .../src/unittest_planning_context.cpp | 2 +- .../src/unittest_planning_context_loaders.cpp | 2 +- ...t_trajectory_blender_transition_window.cpp | 2 +- .../src/unittest_trajectory_functions.cpp | 2 +- .../unittest_trajectory_generator_circ.cpp | 2 +- .../src/unittest_trajectory_generator_lin.cpp | 2 +- .../src/unittest_trajectory_generator_ptp.cpp | 12 +++++----- .../basecmd.h | 2 +- .../cartesianconfiguration.h | 4 ++-- .../cartesianpathconstraintsbuilder.h | 2 +- .../center.h | 2 +- .../circ.h | 4 ++-- .../circ_auxiliary_types.h | 8 +++---- .../command_types_typedef.h | 14 ++++++------ .../gripper.h | 4 ++-- .../prbt_manipulator_ikfast_moveit_plugin.cpp | 4 ++-- .../moveit_ros/moveit_cpp/moveit_cpp.cpp | 2 +- .../src/updater_plugin.cpp | 2 +- .../lazy_free_space_updater.h | 2 +- .../src/lazy_free_space_updater.cpp | 2 +- .../mesh_filter/depth_self_filter_nodelet.h | 6 ++--- .../include/moveit/mesh_filter/mesh_filter.h | 6 ++--- .../moveit/mesh_filter/mesh_filter_base.h | 6 ++--- .../moveit/mesh_filter/stereo_camera_model.h | 4 ++-- .../mesh_filter/src/transform_provider.cpp | 2 +- .../moveit/semantic_world/semantic_world.h | 4 ++-- .../moveit/moveit_cpp/planning_component.h | 12 +++++----- .../planning/moveit_cpp/src/moveit_cpp.cpp | 4 ++-- .../moveit_cpp/src/planning_component.cpp | 10 ++++----- .../moveit_cpp/test/moveit_cpp_test.cpp | 4 ++-- ...re_collision_speed_checking_fcl_bullet.cpp | 12 +++++----- .../src/move_group_interface.cpp | 22 +++++++++---------- .../planning_scene_interface.h | 4 ++-- .../test/move_group_pick_place_test.cpp | 4 ++-- .../test/moveit_cpp_test.cpp | 4 ++-- .../test/subframes_test.cpp | 6 ++--- .../planning_interface/test/test_cleanup.cpp | 2 +- .../moveit/robot_interaction/interaction.h | 2 +- .../robot_interaction/interaction_handler.h | 6 ++--- .../robot_interaction/kinematic_options.h | 4 ++-- .../robot_interaction/kinematic_options_map.h | 4 ++-- .../robot_interaction/locked_robot_state.h | 4 ++-- .../robot_interaction/robot_interaction.h | 8 +++---- .../src/interaction_handler.cpp | 10 ++++----- .../src/interactive_marker_helpers.cpp | 2 +- .../src/kinematic_options.cpp | 2 +- .../src/kinematic_options_map.cpp | 2 +- .../src/locked_robot_state.cpp | 2 +- .../src/robot_interaction.cpp | 10 ++++----- .../test/locked_robot_state_test.cpp | 6 ++--- .../trajectory_cache/trajectory_cache.hpp | 2 +- .../trajectory_cache/src/trajectory_cache.cpp | 8 +++---- .../test/test_trajectory_cache.cpp | 4 ++-- .../motion_planning_display.h | 16 +++++++------- .../motion_planning_frame.h | 12 +++++----- .../motion_planning_param_widget.h | 2 +- .../src/interactive_marker_display.cpp | 2 +- .../src/motion_planning_display.cpp | 20 ++++++++--------- .../src/motion_planning_frame_context.cpp | 12 +++++----- .../motion_planning_frame_joints_widget.cpp | 6 ++--- .../motion_planning_frame_manipulation.cpp | 10 ++++----- .../src/motion_planning_frame_objects.cpp | 12 +++++----- .../src/motion_planning_frame_planning.cpp | 14 ++++++------ .../src/motion_planning_frame_scenes.cpp | 18 +++++++-------- .../src/motion_planning_frame_states.cpp | 10 ++++----- .../src/motion_planning_param_widget.cpp | 4 ++-- .../src/plugin_init.cpp | 2 +- .../planning_scene_display.h | 6 ++--- .../src/planning_scene_display.cpp | 10 ++++----- .../src/plugin_init.cpp | 2 +- .../robot_state_display.h | 4 ++-- .../src/plugin_init.cpp | 2 +- .../planning_scene_render.h | 6 ++--- .../robot_state_visualization.h | 6 ++--- .../trajectory_visualization.h | 12 +++++----- .../src/octomap_render.cpp | 2 +- .../src/planning_link_updater.cpp | 2 +- .../src/planning_scene_render.cpp | 6 ++--- 100 files changed, 261 insertions(+), 263 deletions(-) diff --git a/moveit_core/constraint_samplers/test/pr2_arm_ik.cpp b/moveit_core/constraint_samplers/test/pr2_arm_ik.cpp index b35496a1a4..f521391b21 100644 --- a/moveit_core/constraint_samplers/test/pr2_arm_ik.cpp +++ b/moveit_core/constraint_samplers/test/pr2_arm_ik.cpp @@ -36,7 +36,7 @@ #include #include -#include "pr2_arm_ik.h" +#include "pr2_arm_ik.hpp" /**** List of angles (for reference) ******* th1 = shoulder/turret pan diff --git a/moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.cpp b/moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.cpp index e32ee40eda..715c930786 100644 --- a/moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.cpp +++ b/moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.cpp @@ -42,7 +42,7 @@ #include #include -#include "pr2_arm_kinematics_plugin.h" +#include "pr2_arm_kinematics_plugin.hpp" using namespace KDL; using namespace std; diff --git a/moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.h b/moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.h index 6db3c908d4..c362403b7a 100644 --- a/moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.h +++ b/moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.h @@ -60,7 +60,7 @@ #include -#include "pr2_arm_ik.h" +#include "pr2_arm_ik.hpp" namespace pr2_arm_kinematics { diff --git a/moveit_core/constraint_samplers/test/test_constraint_samplers.cpp b/moveit_core/constraint_samplers/test/test_constraint_samplers.cpp index cfd7cd1378..2e6074c53c 100644 --- a/moveit_core/constraint_samplers/test/test_constraint_samplers.cpp +++ b/moveit_core/constraint_samplers/test/test_constraint_samplers.cpp @@ -52,7 +52,7 @@ #include #include -#include "pr2_arm_kinematics_plugin.h" +#include "pr2_arm_kinematics_plugin.hpp" class LoadPlanningModelsPr2 : public testing::Test { diff --git a/moveit_core/version/CMakeLists.txt b/moveit_core/version/CMakeLists.txt index c67eec7170..3d70285c09 100644 --- a/moveit_core/version/CMakeLists.txt +++ b/moveit_core/version/CMakeLists.txt @@ -25,7 +25,7 @@ add_custom_command( add_custom_target( version_h DEPENDS always_rebuild - COMMENT "Generating version.h") + COMMENT "Generating version.hpp") add_executable(moveit_version version.cpp) add_dependencies(moveit_version version_h) @@ -33,6 +33,6 @@ add_dependencies(moveit_version version_h) target_include_directories(moveit_version PRIVATE ${CMAKE_BINARY_DIR}/include/moveit_core) -install(FILES "${CMAKE_BINARY_DIR}/include/moveit_core/moveit/version.h" +install(FILES "${CMAKE_BINARY_DIR}/include/moveit_core/moveit/version.hpp" DESTINATION include/moveit_core/moveit) install(TARGETS moveit_version RUNTIME DESTINATION bin) diff --git a/moveit_core/version/version.cmake b/moveit_core/version/version.cmake index 60c4723703..13757b7eb3 100644 --- a/moveit_core/version/version.cmake +++ b/moveit_core/version/version.cmake @@ -35,4 +35,4 @@ if(NOT "${MOVEIT_VERSION_EXTRA}" STREQUAL "") endif() configure_file("version.h.in" - "${VERSION_FILE_PATH}/moveit_core/moveit/version.h") + "${VERSION_FILE_PATH}/moveit_core/moveit/version.hpp") diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/README.md b/moveit_kinematics/cached_ik_kinematics_plugin/README.md index 3d7f7c3b05..d0c82167af 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/README.md +++ b/moveit_kinematics/cached_ik_kinematics_plugin/README.md @@ -56,7 +56,7 @@ Below is a complete list of all arguments: The Cached IK Kinematics Plugin is implemented as a wrapper around classed derived from the `kinematics::KinematicsBase` [abstract base class](http://docs.ros.org/en/latest/api/moveit_core/html/cpp/classkinematics_1_1KinematicsBase.html). Wrappers for the `kdl_kinematics_plugin::KDLKinematicsPlugin` and `srv_kinematics_plugin::SrvKinematicsPlugin` classes are already included in the plugin. For any other solver, you can create a new kinematics plugin. The C++ code for doing so is extremely simple; here is the code to create a wrapper for the KDL solver: - #include "cached_ik_kinematics_plugin.h" + #include "cached_ik_kinematics_plugin.hpp" #include #include PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin, kinematics::KinematicsBase); diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h index 0ba16b4142..0768388d33 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h @@ -354,4 +354,4 @@ class CachedMultiTipIKKinematicsPlugin : public CachedIKKinematicsPlugin #include #include -#include "GreedyKCenters.h" -#include "NearestNeighbors.h" +#include "GreedyKCenters.hpp" +#include "NearestNeighbors.hpp" #include namespace cached_ik_kinematics_plugin diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/src/cached_ur_kinematics_plugin.cpp b/moveit_kinematics/cached_ik_kinematics_plugin/src/cached_ur_kinematics_plugin.cpp index c13b2d5a06..14a6ef98d8 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/src/cached_ur_kinematics_plugin.cpp +++ b/moveit_kinematics/cached_ik_kinematics_plugin/src/cached_ur_kinematics_plugin.cpp @@ -34,7 +34,7 @@ /* Author: Mark Moll */ -#include +#include #include #include diff --git a/moveit_kinematics/ikfast_kinematics_plugin/scripts/create_ikfast_moveit_plugin.py b/moveit_kinematics/ikfast_kinematics_plugin/scripts/create_ikfast_moveit_plugin.py index 45495eff73..06c2f103a2 100755 --- a/moveit_kinematics/ikfast_kinematics_plugin/scripts/create_ikfast_moveit_plugin.py +++ b/moveit_kinematics/ikfast_kinematics_plugin/scripts/create_ikfast_moveit_plugin.py @@ -251,7 +251,7 @@ def create_ikfast_package(args): def find_template_dir(): for candidate in [os.path.dirname(__file__) + "/../templates"]: - if os.path.exists(candidate) and os.path.exists(candidate + "/ikfast.h"): + if os.path.exists(candidate) and os.path.exists(candidate + "/ikfast.hpp"): return os.path.realpath(candidate) try: return os.path.join( @@ -303,8 +303,8 @@ def update_ikfast_package(args): # Copy ikfast header file copy_file( - template_dir + "/ikfast.h", - args.ikfast_plugin_pkg_path + "/include/ikfast.h", + template_dir + "/ikfast.hpp", + args.ikfast_plugin_pkg_path + "/include/ikfast.hpp", "ikfast header file", ) # Create ikfast plugin template diff --git a/moveit_planners/ompl/ompl_interface/test/test_constrained_planning_state_space.cpp b/moveit_planners/ompl/ompl_interface/test/test_constrained_planning_state_space.cpp index b411d7b630..223ba97f10 100644 --- a/moveit_planners/ompl/ompl_interface/test/test_constrained_planning_state_space.cpp +++ b/moveit_planners/ompl/ompl_interface/test/test_constrained_planning_state_space.cpp @@ -57,7 +57,7 @@ #include #include -#include "load_test_robot.h" +#include "load_test_robot.hpp" rclcpp::Logger getLogger() { diff --git a/moveit_planners/ompl/ompl_interface/test/test_ompl_constraints.cpp b/moveit_planners/ompl/ompl_interface/test/test_ompl_constraints.cpp index aa06ac75d1..9ea14c5afb 100644 --- a/moveit_planners/ompl/ompl_interface/test/test_ompl_constraints.cpp +++ b/moveit_planners/ompl/ompl_interface/test/test_ompl_constraints.cpp @@ -41,7 +41,7 @@ * NOTE q = joint positions **/ -#include "load_test_robot.h" +#include "load_test_robot.hpp" #include #include diff --git a/moveit_planners/ompl/ompl_interface/test/test_planning_context_manager.cpp b/moveit_planners/ompl/ompl_interface/test/test_planning_context_manager.cpp index 16ecc3fc63..d4fb36a1f9 100644 --- a/moveit_planners/ompl/ompl_interface/test/test_planning_context_manager.cpp +++ b/moveit_planners/ompl/ompl_interface/test/test_planning_context_manager.cpp @@ -50,7 +50,7 @@ * **/ -#include "load_test_robot.h" +#include "load_test_robot.hpp" #include diff --git a/moveit_planners/ompl/ompl_interface/test/test_state_validity_checker.cpp b/moveit_planners/ompl/ompl_interface/test/test_state_validity_checker.cpp index dbf5a69749..926c80b2fa 100644 --- a/moveit_planners/ompl/ompl_interface/test/test_state_validity_checker.cpp +++ b/moveit_planners/ompl/ompl_interface/test/test_state_validity_checker.cpp @@ -48,7 +48,7 @@ * The test do show what is minimally required to create a working StateValidityChecker. **/ -#include "load_test_robot.h" +#include "load_test_robot.hpp" #include #include diff --git a/moveit_planners/ompl/ompl_interface/test/test_threadsafe_state_storage.cpp b/moveit_planners/ompl/ompl_interface/test/test_threadsafe_state_storage.cpp index fd6711682d..8034a69db2 100644 --- a/moveit_planners/ompl/ompl_interface/test/test_threadsafe_state_storage.cpp +++ b/moveit_planners/ompl/ompl_interface/test/test_threadsafe_state_storage.cpp @@ -38,7 +38,7 @@ This test checks if a state can be set in TSSafeStateStorage and correctly retri The skeleton of this test was taken from test_state_validity_checker.cpp by Jeroen De Maeyer. */ -#include "load_test_robot.h" +#include "load_test_robot.hpp" #include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h index 9d7b70431c..34345d4b35 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h @@ -37,7 +37,7 @@ #include #include -#include "cartesian_trajectory_point.h" +#include "cartesian_trajectory_point.hpp" namespace pilz_industrial_motion_planner { diff --git a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator_lin.cpp b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator_lin.cpp index 941290b90e..cee73b29fa 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator_lin.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator_lin.cpp @@ -32,18 +32,16 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include -#include +#include #include #include -#include -#include + +#include #include -#include -#include -#include + #include #include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_command_list_manager.cpp b/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_command_list_manager.cpp index 46dfa8300e..2f0fb62c72 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_command_list_manager.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_command_list_manager.cpp @@ -54,7 +54,7 @@ #include #include -#include "test_utils.h" +#include "test_utils.hpp" #include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_command_planning.cpp b/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_command_planning.cpp index 26929b6513..abcab274cc 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_command_planning.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_command_planning.cpp @@ -52,7 +52,7 @@ #include #include -#include "test_utils.h" +#include "test_utils.hpp" const double EPSILON = 1.0e-6; const std::string PLAN_SERVICE_NAME = "/plan_kinematic_path"; diff --git a/moveit_planners/pilz_industrial_motion_planner/test/test_utils.cpp b/moveit_planners/pilz_industrial_motion_planner/test/test_utils.cpp index 5dcfad0cde..fca5e3b220 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/test_utils.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/test_utils.cpp @@ -39,7 +39,7 @@ #include #include -#include "test_utils.h" +#include "test_utils.hpp" // Logger static const rclcpp::Logger LOGGER = rclcpp::get_logger("pilz_industrial_motion_planner.test_utils"); diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_pilz_industrial_motion_planner.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_pilz_industrial_motion_planner.cpp index 24493d2cdc..2d0109f1e5 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_pilz_industrial_motion_planner.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_pilz_industrial_motion_planner.cpp @@ -40,7 +40,7 @@ #include #include -#include "test_utils.h" +#include "test_utils.hpp" #include diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context.cpp index a0540e5360..232f866092 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context.cpp @@ -47,7 +47,7 @@ #include #include -#include "test_utils.h" +#include "test_utils.hpp" // parameters from parameter server const std::string PARAM_PLANNING_GROUP_NAME("planning_group"); diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context_loaders.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context_loaders.cpp index 0f937f99ca..8dc23da3c0 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context_loaders.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context_loaders.cpp @@ -41,7 +41,7 @@ #include -#include "test_utils.h" +#include "test_utils.hpp" #include diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_blender_transition_window.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_blender_transition_window.cpp index 3a109cddcb..c3d524256d 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_blender_transition_window.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_blender_transition_window.cpp @@ -52,7 +52,7 @@ #include #include #include -#include "test_utils.h" +#include "test_utils.hpp" #include diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_functions.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_functions.cpp index 66cee20108..5bfaba862e 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_functions.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_functions.cpp @@ -57,7 +57,7 @@ #include #include #include -#include "test_utils.h" +#include "test_utils.hpp" #define _USE_MATH_DEFINES diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_generator_circ.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_generator_circ.cpp index 7e462e287a..5c9ba0b4b0 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_generator_circ.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_generator_circ.cpp @@ -47,7 +47,7 @@ #include #include #include -#include "test_utils.h" +#include "test_utils.hpp" #include diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_generator_lin.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_generator_lin.cpp index cde5c06618..77ebfd0b8b 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_generator_lin.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_generator_lin.cpp @@ -40,7 +40,7 @@ #include #include #include -#include "test_utils.h" +#include "test_utils.hpp" #include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_generator_ptp.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_generator_ptp.cpp index 6a423b6f45..3fcb254aac 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_generator_ptp.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_generator_ptp.cpp @@ -36,13 +36,13 @@ #include -#include -#include -#include "test_utils.h" +#include +#include +#include "test_utils.hpp" -#include -#include -#include +#include +#include +#include #include #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h index 4c1cabef2d..19649f14fe 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h @@ -36,7 +36,7 @@ #include -#include "motioncmd.h" +#include "motioncmd.hpp" namespace pilz_industrial_motion_planner_testutils { diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h index b6057abdb3..480a5d55ef 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h @@ -45,8 +45,8 @@ #include #include -#include "robotconfiguration.h" -#include "jointconfiguration.h" +#include "robotconfiguration.hpp" +#include "jointconfiguration.hpp" namespace pilz_industrial_motion_planner_testutils { diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h index ca05ab7a06..d684738597 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h @@ -38,7 +38,7 @@ #include -#include "cartesianconfiguration.h" +#include "cartesianconfiguration.hpp" namespace pilz_industrial_motion_planner_testutils { diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h index 39acff221d..161417ac33 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h @@ -34,7 +34,7 @@ #pragma once -#include "circauxiliary.h" +#include "circauxiliary.hpp" namespace pilz_industrial_motion_planner_testutils { diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h index a6560814e1..cc48d853e0 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h @@ -36,8 +36,8 @@ #include -#include "basecmd.h" -#include "circauxiliary.h" +#include "basecmd.hpp" +#include "circauxiliary.hpp" namespace pilz_industrial_motion_planner_testutils { diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h index 0109def4f7..dac95fc0ca 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h @@ -34,10 +34,10 @@ #pragma once -#include "center.h" -#include "interim.h" -#include "cartesianconfiguration.h" -#include "cartesianpathconstraintsbuilder.h" +#include "center.hpp" +#include "interim.hpp" +#include "cartesianconfiguration.hpp" +#include "cartesianpathconstraintsbuilder.hpp" namespace pilz_industrial_motion_planner_testutils { diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h index 697cc5781f..a1a37ba6eb 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h @@ -34,13 +34,13 @@ #pragma once -#include "ptp.h" -#include "lin.h" -#include "circ.h" -#include "gripper.h" -#include "jointconfiguration.h" -#include "cartesianconfiguration.h" -#include "circ_auxiliary_types.h" +#include "ptp.hpp" +#include "lin.hpp" +#include "circ.hpp" +#include "gripper.hpp" +#include "jointconfiguration.hpp" +#include "cartesianconfiguration.hpp" +#include "circ_auxiliary_types.hpp" #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h index 5b3aca63c1..645fb84304 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h @@ -34,8 +34,8 @@ #pragma once -#include "ptp.h" -#include "jointconfiguration.h" +#include "ptp.hpp" +#include "jointconfiguration.hpp" namespace pilz_industrial_motion_planner_testutils { diff --git a/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/src/prbt_manipulator_ikfast_moveit_plugin.cpp b/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/src/prbt_manipulator_ikfast_moveit_plugin.cpp index d035de8c15..4df96995c5 100644 --- a/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/src/prbt_manipulator_ikfast_moveit_plugin.cpp +++ b/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/src/prbt_manipulator_ikfast_moveit_plugin.cpp @@ -50,8 +50,8 @@ #include #include #include -#include -#include +#include +#include #include using namespace moveit::core; diff --git a/moveit_py/src/moveit/moveit_ros/moveit_cpp/moveit_cpp.cpp b/moveit_py/src/moveit/moveit_ros/moveit_cpp/moveit_cpp.cpp index 40a037675a..a0318ec127 100644 --- a/moveit_py/src/moveit/moveit_ros/moveit_cpp/moveit_cpp.cpp +++ b/moveit_py/src/moveit/moveit_ros/moveit_cpp/moveit_cpp.cpp @@ -34,7 +34,7 @@ /* Author: Peter David Fagan */ -#include "moveit_cpp.h" +#include "moveit_cpp.hpp" #include namespace moveit_py diff --git a/moveit_ros/perception/depth_image_octomap_updater/src/updater_plugin.cpp b/moveit_ros/perception/depth_image_octomap_updater/src/updater_plugin.cpp index a32b72a23e..ad529c16ad 100644 --- a/moveit_ros/perception/depth_image_octomap_updater/src/updater_plugin.cpp +++ b/moveit_ros/perception/depth_image_octomap_updater/src/updater_plugin.cpp @@ -35,6 +35,6 @@ /* Author: Ioan Sucan */ #include -#include +#include CLASS_LOADER_REGISTER_CLASS(occupancy_map_monitor::DepthImageOctomapUpdater, occupancy_map_monitor::OccupancyMapUpdater) diff --git a/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h b/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h index cea8f3064b..0aa4276b54 100644 --- a/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h +++ b/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h @@ -36,7 +36,7 @@ #pragma once -#include +#include #include #include #include diff --git a/moveit_ros/perception/lazy_free_space_updater/src/lazy_free_space_updater.cpp b/moveit_ros/perception/lazy_free_space_updater/src/lazy_free_space_updater.cpp index fff1edf040..9f092f4181 100644 --- a/moveit_ros/perception/lazy_free_space_updater/src/lazy_free_space_updater.cpp +++ b/moveit_ros/perception/lazy_free_space_updater/src/lazy_free_space_updater.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include +#include #include #include #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h index f67e0869a9..1b531d2311 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h @@ -38,9 +38,9 @@ #include #include -#include -#include -#include +#include +#include +#include #include #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h index abe6bb27b9..37448b09c7 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h @@ -37,9 +37,9 @@ #pragma once #include -#include -#include -#include +#include +#include +#include // forward declarations namespace shapes diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h index 879a9d87bc..c6aa33bfb1 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h @@ -37,9 +37,9 @@ #pragma once #include -#include -#include -#include +#include +#include +#include #include // for Isometry3d #include #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h index 033dd67e30..db5ac3d289 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h @@ -36,10 +36,10 @@ #pragma once -#include +#include #include -#include +#include namespace mesh_filter { diff --git a/moveit_ros/perception/mesh_filter/src/transform_provider.cpp b/moveit_ros/perception/mesh_filter/src/transform_provider.cpp index 44617c4322..a21695ed70 100644 --- a/moveit_ros/perception/mesh_filter/src/transform_provider.cpp +++ b/moveit_ros/perception/mesh_filter/src/transform_provider.cpp @@ -34,7 +34,7 @@ /* Author: Suat Gedikli */ -#include +#include #include #include #include diff --git a/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h index 1f56067e12..b46d17731e 100644 --- a/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h +++ b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h @@ -37,8 +37,8 @@ #pragma once #include -#include -#include +#include +#include #include #include #include diff --git a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h index 88668e1f01..b8b74367e7 100644 --- a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h +++ b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h @@ -38,14 +38,14 @@ #pragma once #include -#include -#include +#include +#include #include #include -#include -#include -#include -#include +#include +#include +#include +#include #include namespace moveit_cpp diff --git a/moveit_ros/planning/moveit_cpp/src/moveit_cpp.cpp b/moveit_ros/planning/moveit_cpp/src/moveit_cpp.cpp index 410edc25ff..abc683745c 100644 --- a/moveit_ros/planning/moveit_cpp/src/moveit_cpp.cpp +++ b/moveit_ros/planning/moveit_cpp/src/moveit_cpp.cpp @@ -36,9 +36,9 @@ #include -#include +#include #include -#include +#include #include #include #include diff --git a/moveit_ros/planning/moveit_cpp/src/planning_component.cpp b/moveit_ros/planning/moveit_cpp/src/planning_component.cpp index b3494a4a50..945a979e16 100644 --- a/moveit_ros/planning/moveit_cpp/src/planning_component.cpp +++ b/moveit_ros/planning/moveit_cpp/src/planning_component.cpp @@ -36,11 +36,11 @@ #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include #include diff --git a/moveit_ros/planning/moveit_cpp/test/moveit_cpp_test.cpp b/moveit_ros/planning/moveit_cpp/test/moveit_cpp_test.cpp index 2191d9f112..8d49561f56 100644 --- a/moveit_ros/planning/moveit_cpp/test/moveit_cpp_test.cpp +++ b/moveit_ros/planning/moveit_cpp/test/moveit_cpp_test.cpp @@ -43,8 +43,8 @@ #include // Main class -#include -#include +#include +#include // Msgs #include diff --git a/moveit_ros/planning/planning_components_tools/src/compare_collision_speed_checking_fcl_bullet.cpp b/moveit_ros/planning/planning_components_tools/src/compare_collision_speed_checking_fcl_bullet.cpp index 1aa98f230d..76f55f71e2 100644 --- a/moveit_ros/planning/planning_components_tools/src/compare_collision_speed_checking_fcl_bullet.cpp +++ b/moveit_ros/planning/planning_components_tools/src/compare_collision_speed_checking_fcl_bullet.cpp @@ -34,15 +34,15 @@ /* Author: Jens Petit */ -#include -#include -#include -#include +#include +#include +#include +#include #include #include -#include -#include +#include +#include static const std::string ROBOT_DESCRIPTION = "robot_description"; diff --git a/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp b/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp index e729707913..b7238268d5 100644 --- a/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp +++ b/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp @@ -40,23 +40,23 @@ #include #include #include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include #include #include #include #include #include #include -#include +#include #include #include diff --git a/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h b/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h index 4fbe501e31..e581ab5a42 100644 --- a/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h +++ b/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include #include #include #include diff --git a/moveit_ros/planning_interface/test/move_group_pick_place_test.cpp b/moveit_ros/planning_interface/test/move_group_pick_place_test.cpp index b866015e00..602cc39daf 100644 --- a/moveit_ros/planning_interface/test/move_group_pick_place_test.cpp +++ b/moveit_ros/planning_interface/test/move_group_pick_place_test.cpp @@ -49,8 +49,8 @@ #include // MoveIt -#include -#include +#include +#include // TF2 #include diff --git a/moveit_ros/planning_interface/test/moveit_cpp_test.cpp b/moveit_ros/planning_interface/test/moveit_cpp_test.cpp index 4306daad63..615f666bd6 100644 --- a/moveit_ros/planning_interface/test/moveit_cpp_test.cpp +++ b/moveit_ros/planning_interface/test/moveit_cpp_test.cpp @@ -43,8 +43,8 @@ #include // Main class -#include -#include +#include +#include // Msgs #include diff --git a/moveit_ros/planning_interface/test/subframes_test.cpp b/moveit_ros/planning_interface/test/subframes_test.cpp index 1f07dd30d8..8cafabfb77 100644 --- a/moveit_ros/planning_interface/test/subframes_test.cpp +++ b/moveit_ros/planning_interface/test/subframes_test.cpp @@ -50,9 +50,9 @@ #include // MoveIt -#include -#include -#include +#include +#include +#include // TF2 #include diff --git a/moveit_ros/planning_interface/test/test_cleanup.cpp b/moveit_ros/planning_interface/test/test_cleanup.cpp index d807425057..99b1c91ebc 100644 --- a/moveit_ros/planning_interface/test/test_cleanup.cpp +++ b/moveit_ros/planning_interface/test/test_cleanup.cpp @@ -31,7 +31,7 @@ /* Author: Robert Haschke */ -#include +#include #include int main(int argc, char** argv) diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h index 9f7fd9a197..6fa5620e43 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h @@ -39,7 +39,7 @@ #include #include #include -#include +#include #include #include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h index 66c5f1520b..1221ffb3d4 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h @@ -37,9 +37,9 @@ #pragma once #include -#include -#include -//#include +#include +#include +//#include #include #include #include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h index 4fc0b8650c..5a63ea5d92 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include namespace robot_interaction { diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h index 154479ff2b..5ffb947fba 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h @@ -36,11 +36,11 @@ #pragma once -#include +#include #include #include -#include +#include namespace robot_interaction { diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h index 2e00e47e08..bc5aa30f54 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h @@ -37,8 +37,8 @@ #pragma once -#include -#include +#include +#include #include #include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h index 31bf726f21..d98503751b 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h @@ -39,9 +39,9 @@ #include #include #include -#include -#include -#include +#include +#include +#include #include #include #include @@ -49,7 +49,7 @@ // This is needed for legacy code that includes robot_interaction.h but not // interaction_handler.h -#include +#include namespace interactive_markers { diff --git a/moveit_ros/robot_interaction/src/interaction_handler.cpp b/moveit_ros/robot_interaction/src/interaction_handler.cpp index a56ac384cc..8d79f91519 100644 --- a/moveit_ros/robot_interaction/src/interaction_handler.cpp +++ b/moveit_ros/robot_interaction/src/interaction_handler.cpp @@ -36,11 +36,11 @@ /* Author: Ioan Sucan, Adam Leeper */ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include #include #include diff --git a/moveit_ros/robot_interaction/src/interactive_marker_helpers.cpp b/moveit_ros/robot_interaction/src/interactive_marker_helpers.cpp index f4c401d419..fe6fce7250 100644 --- a/moveit_ros/robot_interaction/src/interactive_marker_helpers.cpp +++ b/moveit_ros/robot_interaction/src/interactive_marker_helpers.cpp @@ -35,7 +35,7 @@ /* Author: Ioan Sucan, Acorn Pooley, Adam Leeper */ #include -#include +#include #include #include diff --git a/moveit_ros/robot_interaction/src/kinematic_options.cpp b/moveit_ros/robot_interaction/src/kinematic_options.cpp index de704ae6e9..2c7d1be874 100644 --- a/moveit_ros/robot_interaction/src/kinematic_options.cpp +++ b/moveit_ros/robot_interaction/src/kinematic_options.cpp @@ -34,7 +34,7 @@ /* Author: Acorn Pooley */ -#include +#include #include #include diff --git a/moveit_ros/robot_interaction/src/kinematic_options_map.cpp b/moveit_ros/robot_interaction/src/kinematic_options_map.cpp index 30c0d23879..2cbe343710 100644 --- a/moveit_ros/robot_interaction/src/kinematic_options_map.cpp +++ b/moveit_ros/robot_interaction/src/kinematic_options_map.cpp @@ -34,7 +34,7 @@ /* Author: Acorn Pooley */ -#include +#include // These strings have no content. They are compared by address. const std::string robot_interaction::KinematicOptionsMap::DEFAULT = ""; diff --git a/moveit_ros/robot_interaction/src/locked_robot_state.cpp b/moveit_ros/robot_interaction/src/locked_robot_state.cpp index d19402f062..15b8d0c845 100644 --- a/moveit_ros/robot_interaction/src/locked_robot_state.cpp +++ b/moveit_ros/robot_interaction/src/locked_robot_state.cpp @@ -36,7 +36,7 @@ /* Author: Ioan Sucan, Acorn Pooley */ -#include +#include robot_interaction::LockedRobotState::LockedRobotState(const moveit::core::RobotState& state) : state_(std::make_shared(state)) diff --git a/moveit_ros/robot_interaction/src/robot_interaction.cpp b/moveit_ros/robot_interaction/src/robot_interaction.cpp index d641cd040c..23d5cbacd5 100644 --- a/moveit_ros/robot_interaction/src/robot_interaction.cpp +++ b/moveit_ros/robot_interaction/src/robot_interaction.cpp @@ -35,11 +35,11 @@ /* Author: Ioan Sucan, Adam Leeper */ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include #include #include diff --git a/moveit_ros/robot_interaction/test/locked_robot_state_test.cpp b/moveit_ros/robot_interaction/test/locked_robot_state_test.cpp index 0d887a6acf..7808dc3ab0 100644 --- a/moveit_ros/robot_interaction/test/locked_robot_state_test.cpp +++ b/moveit_ros/robot_interaction/test/locked_robot_state_test.cpp @@ -36,9 +36,9 @@ /* Author: Acorn Pooley, Ioan Sucan */ #include -#include -#include -#include +#include +#include +#include #include static const char* const URDF_STR = diff --git a/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.hpp b/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.hpp index 2af5058840..87288cba4d 100644 --- a/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.hpp +++ b/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.hpp @@ -37,7 +37,7 @@ #include // moveit modules -#include +#include #include namespace moveit_ros diff --git a/moveit_ros/trajectory_cache/src/trajectory_cache.cpp b/moveit_ros/trajectory_cache/src/trajectory_cache.cpp index 81bceebe5c..f74e9a15ca 100644 --- a/moveit_ros/trajectory_cache/src/trajectory_cache.cpp +++ b/moveit_ros/trajectory_cache/src/trajectory_cache.cpp @@ -20,10 +20,10 @@ #include #include -#include -#include -#include -#include +#include +#include +#include +#include #include #include diff --git a/moveit_ros/trajectory_cache/test/test_trajectory_cache.cpp b/moveit_ros/trajectory_cache/test/test_trajectory_cache.cpp index dfe8ef7e47..425aa9cd76 100644 --- a/moveit_ros/trajectory_cache/test/test_trajectory_cache.cpp +++ b/moveit_ros/trajectory_cache/test/test_trajectory_cache.cpp @@ -18,8 +18,8 @@ #include -#include -#include +#include +#include #include #include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h index 62cfcd0995..4f5a2b9242 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h @@ -38,17 +38,17 @@ #include #include -#include -#include +#include +#include #ifndef Q_MOC_RUN -#include -#include -#include +#include +#include +#include -#include -#include -#include +#include +#include +#include #include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h index 6288c349ab..67e44bb40a 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h @@ -41,13 +41,13 @@ #include #ifndef Q_MOC_RUN -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include // TODO (ddengster): Enable when moveit_ros_perception is ported -// #include +// #include #include #include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h index 3935103719..157fd4a1f9 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h @@ -36,7 +36,7 @@ #pragma once -#include +#include #include namespace moveit diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/interactive_marker_display.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/interactive_marker_display.cpp index bdd67a9a65..ad791e7053 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/interactive_marker_display.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/interactive_marker_display.cpp @@ -39,7 +39,7 @@ #include -#include +#include namespace rviz_default_plugins { diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp index 110fe48915..fd22e4406e 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp @@ -34,15 +34,15 @@ /* Author: Ioan Sucan, Dave Coleman, Adam Leeper, Sachin Chitta */ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include #include -#include +#include #include #include @@ -62,13 +62,13 @@ #include #include -#include -#include +#include +#include #include -#include "ui_motion_planning_rviz_plugin_frame.h" -#include +#include "ui_motion_planning_rviz_plugin_frame.hpp" +#include #include namespace moveit_rviz_plugin diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_context.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_context.cpp index 497f2655fd..de8b9d0516 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_context.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_context.cpp @@ -33,11 +33,11 @@ *********************************************************************/ /* Author: Ioan Sucan */ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include #include @@ -45,7 +45,7 @@ #include #include -#include "ui_motion_planning_rviz_plugin_frame.h" +#include "ui_motion_planning_rviz_plugin_frame.hpp" namespace moveit_rviz_plugin { diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_joints_widget.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_joints_widget.cpp index 3157891ec2..a649c7f86c 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_joints_widget.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_joints_widget.cpp @@ -34,10 +34,10 @@ /* Author: Robert Haschke */ -#include -#include +#include +#include -#include "ui_motion_planning_rviz_plugin_frame_joints.h" +#include "ui_motion_planning_rviz_plugin_frame_joints.hpp" #include #include #include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_manipulation.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_manipulation.cpp index 5c20b48776..808c7daa64 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_manipulation.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_manipulation.cpp @@ -34,16 +34,16 @@ /* Author: Sachin Chitta */ -#include -#include +#include +#include -#include -#include +#include +#include #include #include -#include "ui_motion_planning_rviz_plugin_frame.h" +#include "ui_motion_planning_rviz_plugin_frame.hpp" namespace moveit_rviz_plugin { diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_objects.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_objects.cpp index 4d473bbf11..fdfa5e7bc5 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_objects.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_objects.cpp @@ -33,12 +33,12 @@ *********************************************************************/ /* Author: Ioan Sucan, Mario Prats */ -#include +#include -#include -#include -#include -#include +#include +#include +#include +#include #include @@ -53,7 +53,7 @@ #include #include -#include "ui_motion_planning_rviz_plugin_frame.h" +#include "ui_motion_planning_rviz_plugin_frame.hpp" namespace { diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_planning.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_planning.cpp index 746685ed43..8bc632a558 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_planning.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_planning.cpp @@ -34,19 +34,19 @@ /* Author: Ioan Sucan */ -#include -#include -#include +#include +#include +#include -#include -#include +#include +#include #include #include #include -#include +#include -#include "ui_motion_planning_rviz_plugin_frame.h" +#include "ui_motion_planning_rviz_plugin_frame.hpp" namespace moveit_rviz_plugin { diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_scenes.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_scenes.cpp index 245b750269..e5f99b4d51 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_scenes.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_scenes.cpp @@ -33,15 +33,15 @@ *********************************************************************/ /* Author: Ioan Sucan */ -#include -#include -#include +#include +#include +#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include @@ -51,7 +51,7 @@ #include #include -#include "ui_motion_planning_rviz_plugin_frame.h" +#include "ui_motion_planning_rviz_plugin_frame.hpp" #include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_states.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_states.cpp index 35d84a425e..90f06b1519 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_states.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_states.cpp @@ -33,16 +33,16 @@ *********************************************************************/ /* Author: Mario Prats, Ioan Sucan */ -#include +#include -#include -#include -#include +#include +#include +#include #include #include -#include "ui_motion_planning_rviz_plugin_frame.h" +#include "ui_motion_planning_rviz_plugin_frame.hpp" namespace moveit_rviz_plugin { diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_param_widget.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_param_widget.cpp index b896492ac8..58ce158323 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_param_widget.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_param_widget.cpp @@ -34,8 +34,8 @@ /* Author: Robert Haschke */ -#include -#include +#include +#include #include #include #include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/plugin_init.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/plugin_init.cpp index 2ab60fe715..e67351449b 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/plugin_init.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/plugin_init.cpp @@ -35,6 +35,6 @@ /* Author: Ioan Sucan */ #include -#include +#include CLASS_LOADER_REGISTER_CLASS(moveit_rviz_plugin::MotionPlanningDisplay, rviz_common::Display) diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h index 5fa7fe9019..e2bfd706ee 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h @@ -41,13 +41,13 @@ #include #include #ifndef Q_MOC_RUN -#include -#include +#include +#include #include #include #endif -#include +#include namespace Ogre { diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/src/planning_scene_display.cpp b/moveit_ros/visualization/planning_scene_rviz_plugin/src/planning_scene_display.cpp index 859d0c0b48..4bce580a25 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/src/planning_scene_display.cpp +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/src/planning_scene_display.cpp @@ -35,10 +35,10 @@ /* Author: Ioan Sucan */ -#include -#include -#include -#include +#include +#include +#include +#include #include #include @@ -55,7 +55,7 @@ #include #include -#include +#include #include namespace moveit_rviz_plugin diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/src/plugin_init.cpp b/moveit_ros/visualization/planning_scene_rviz_plugin/src/plugin_init.cpp index 019342fa8d..8e9fdfa85f 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/src/plugin_init.cpp +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/src/plugin_init.cpp @@ -35,6 +35,6 @@ /* Author: Ioan Sucan */ #include -#include +#include CLASS_LOADER_REGISTER_CLASS(moveit_rviz_plugin::PlanningSceneDisplay, rviz_common::Display) diff --git a/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h b/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h index 3661a09581..19e4c48920 100644 --- a/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h +++ b/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h @@ -39,8 +39,8 @@ #include #ifndef Q_MOC_RUN -#include -#include +#include +#include #include #include #endif diff --git a/moveit_ros/visualization/robot_state_rviz_plugin/src/plugin_init.cpp b/moveit_ros/visualization/robot_state_rviz_plugin/src/plugin_init.cpp index e26e9b594d..7b07283c54 100644 --- a/moveit_ros/visualization/robot_state_rviz_plugin/src/plugin_init.cpp +++ b/moveit_ros/visualization/robot_state_rviz_plugin/src/plugin_init.cpp @@ -35,6 +35,6 @@ /* Author: Ioan Sucan */ #include -#include +#include CLASS_LOADER_REGISTER_CLASS(moveit_rviz_plugin::RobotStateDisplay, rviz_common::Display) diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h index 06ab1d8fda..cffb6d60d1 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h @@ -36,9 +36,9 @@ #pragma once -#include -#include -#include +#include +#include +#include #include #include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h index fae4c85c29..c8f08a74aa 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h @@ -36,9 +36,9 @@ #pragma once -#include -#include -#include +#include +#include +#include #include namespace moveit_rviz_plugin diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h index 2e11e94c61..9a52e96e65 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h @@ -36,7 +36,7 @@ #pragma once -#include +#include #include #include #include @@ -45,12 +45,12 @@ #include #ifndef Q_MOC_RUN -#include -#include +#include +#include #include -#include -#include -#include +#include +#include +#include #include #endif diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/src/octomap_render.cpp b/moveit_ros/visualization/rviz_plugin_render_tools/src/octomap_render.cpp index 393d11bc9e..9ade5f9e7e 100755 --- a/moveit_ros/visualization/rviz_plugin_render_tools/src/octomap_render.cpp +++ b/moveit_ros/visualization/rviz_plugin_render_tools/src/octomap_render.cpp @@ -34,7 +34,7 @@ /* Author: Julius Kammerl */ -#include +#include #include #include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/src/planning_link_updater.cpp b/moveit_ros/visualization/rviz_plugin_render_tools/src/planning_link_updater.cpp index b01dd7978a..11f0c9f2f1 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/src/planning_link_updater.cpp +++ b/moveit_ros/visualization/rviz_plugin_render_tools/src/planning_link_updater.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include +#include #include bool moveit_rviz_plugin::PlanningLinkUpdater::getLinkTransforms(const std::string& link_name, diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/src/planning_scene_render.cpp b/moveit_ros/visualization/rviz_plugin_render_tools/src/planning_scene_render.cpp index 10b12aa76b..6493462198 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/src/planning_scene_render.cpp +++ b/moveit_ros/visualization/rviz_plugin_render_tools/src/planning_scene_render.cpp @@ -34,9 +34,9 @@ /* Author: Ioan Sucan */ -#include -#include -#include +#include +#include +#include #include #include From fcc088ccded1c5ad63f2a3dfb7c1db3323ccaf1a Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Sun, 17 Nov 2024 16:07:18 +0000 Subject: [PATCH 02/53] Replaces moveit imports from .h to .hpp --- .../collision_detector_allocator_allvalid.h | 6 ++-- .../allvalid/collision_env_allvalid.h | 2 +- .../collision_detection/collision_common.h | 2 +- .../collision_detector_allocator.h | 4 +-- .../collision_detection/collision_env.h | 8 ++--- .../collision_detection/collision_matrix.h | 4 +-- .../collision_octomap_filter.h | 4 +-- .../collision_detection/collision_plugin.h | 6 ++-- .../collision_plugin_cache.h | 4 +-- .../collision_detection/collision_tools.h | 2 +- .../test_collision_common_panda.h | 18 +++++------ .../test_collision_common_pr2.h | 14 ++++----- .../moveit/collision_detection/world.h | 4 +-- .../moveit/collision_detection/world_diff.h | 4 +-- .../src/allvalid/collision_env_allvalid.cpp | 4 +-- .../src/collision_common.cpp | 2 +- .../collision_detection/src/collision_env.cpp | 2 +- .../src/collision_matrix.cpp | 2 +- .../src/collision_octomap_filter.cpp | 4 +-- .../src/collision_plugin_cache.cpp | 2 +- .../src/collision_tools.cpp | 2 +- moveit_core/collision_detection/src/world.cpp | 4 +-- .../collision_detection/src/world_diff.cpp | 2 +- .../test/test_all_valid.cpp | 4 +-- .../collision_detection/test/test_world.cpp | 2 +- .../test/test_world_diff.cpp | 2 +- .../bullet_integration/basic_types.h | 2 +- .../bullet_integration/bullet_bvh_manager.h | 4 +-- .../bullet_cast_bvh_manager.h | 6 ++-- .../bullet_discrete_bvh_manager.h | 6 ++-- .../bullet_integration/bullet_utils.h | 10 +++---- .../contact_checker_common.h | 6 ++-- .../bullet_integration/ros_bullet_utils.h | 2 +- .../collision_detector_allocator_bullet.h | 6 ++-- .../collision_detector_bullet_plugin_loader.h | 4 +-- .../collision_env_bullet.h | 6 ++-- .../bullet_integration/bullet_bvh_manager.cpp | 2 +- .../bullet_cast_bvh_manager.cpp | 4 +-- .../bullet_discrete_bvh_manager.cpp | 4 +-- .../src/bullet_integration/bullet_utils.cpp | 4 +-- .../contact_checker_common.cpp | 4 +-- .../bullet_integration/ros_bullet_utils.cpp | 2 +- ...ollision_detector_bullet_plugin_loader.cpp | 2 +- .../src/collision_env_bullet.cpp | 8 ++--- .../test_bullet_collision_detection_panda.cpp | 4 +-- .../test_bullet_collision_detection_pr2.cpp | 4 +-- ...t_bullet_continuous_collision_checking.cpp | 16 +++++----- .../collision_common.h | 8 ++--- .../collision_detector_allocator_fcl.h | 6 ++-- .../collision_detector_fcl_plugin_loader.h | 4 +-- .../collision_env_fcl.h | 4 +-- .../src/collision_common.cpp | 4 +-- .../collision_detector_fcl_plugin_loader.cpp | 2 +- .../src/collision_env_fcl.cpp | 8 ++--- .../test_fcl_collision_detection_panda.cpp | 4 +-- .../test/test_fcl_collision_detection_pr2.cpp | 4 +-- .../test/test_fcl_env.cpp | 12 ++++---- .../collision_common_distance_field.h | 10 +++---- ...lision_detector_allocator_distance_field.h | 4 +-- .../collision_detector_allocator_hybrid.h | 6 ++-- .../collision_distance_field_types.h | 6 ++-- .../collision_env_distance_field.h | 10 +++---- .../collision_env_hybrid.h | 8 ++--- .../src/collision_common_distance_field.cpp | 2 +- .../src/collision_distance_field_types.cpp | 6 ++-- .../src/collision_env_distance_field.cpp | 10 +++---- .../src/collision_env_hybrid.cpp | 4 +-- .../test/test_collision_distance_field.cpp | 12 ++++---- .../constraint_samplers/constraint_sampler.h | 4 +-- .../constraint_sampler_allocator.h | 4 +-- .../constraint_sampler_manager.h | 4 +-- .../constraint_sampler_tools.h | 2 +- .../default_constraint_samplers.h | 4 +-- .../union_constraint_sampler.h | 2 +- .../src/constraint_sampler.cpp | 2 +- .../src/constraint_sampler_manager.cpp | 6 ++-- .../src/constraint_sampler_tools.cpp | 4 +-- .../src/default_constraint_samplers.cpp | 2 +- .../src/union_constraint_sampler.cpp | 4 +-- .../test/pr2_arm_kinematics_plugin.cpp | 2 +- .../test/pr2_arm_kinematics_plugin.h | 4 +-- .../test/test_constraint_samplers.cpp | 20 ++++++------- .../controller_manager/controller_manager.h | 2 +- .../moveit/distance_field/distance_field.h | 6 ++-- .../propagation_distance_field.h | 4 +-- .../moveit/distance_field/voxel_grid.h | 2 +- .../distance_field/src/distance_field.cpp | 4 +-- .../src/find_internal_points.cpp | 2 +- .../src/propagation_distance_field.cpp | 2 +- .../test/test_distance_field.cpp | 6 ++-- .../distance_field/test/test_voxel_grid.cpp | 2 +- .../moveit/dynamics_solver/dynamics_solver.h | 2 +- .../dynamics_solver/src/dynamics_solver.cpp | 2 +- moveit_core/exceptions/src/exceptions.cpp | 2 +- .../kinematic_constraint.h | 10 +++---- .../moveit/kinematic_constraints/utils.h | 2 +- .../src/kinematic_constraint.cpp | 6 ++-- .../kinematic_constraints/src/utils.cpp | 4 +-- .../test/test_constraints.cpp | 4 +-- .../test/test_orientation_constraints.cpp | 4 +-- .../moveit/kinematics_base/kinematics_base.h | 4 +-- .../kinematics_base/src/kinematics_base.cpp | 4 +-- .../kinematics_metrics/kinematics_metrics.h | 2 +- .../src/kinematics_metrics.cpp | 2 +- .../include/moveit/macros/class_forward.h | 2 +- .../acceleration_filter.h | 6 ++-- .../butterworth_filter.h | 4 +-- .../online_signal_smoothing/ruckig_filter.h | 4 +-- .../smoothing_base_class.h | 4 +-- .../src/acceleration_filter.cpp | 2 +- .../src/butterworth_filter.cpp | 2 +- .../src/ruckig_filter.cpp | 2 +- .../src/smoothing_base_class.cpp | 2 +- .../test/test_acceleration_filter.cpp | 4 +-- .../test/test_butterworth_filter.cpp | 2 +- .../planning_interface/planning_interface.h | 8 ++--- .../planning_request_adapter.h | 6 ++-- .../planning_interface/planning_response.h | 4 +-- .../planning_response_adapter.h | 4 +-- .../src/planning_interface.cpp | 2 +- .../src/planning_response.cpp | 4 +-- .../moveit/planning_scene/planning_scene.h | 22 +++++++------- .../planning_scene/src/planning_scene.cpp | 18 +++++------ .../test/test_collision_objects.cpp | 6 ++-- .../test/test_multi_threaded.cpp | 12 ++++---- .../test/test_planning_scene.cpp | 12 ++++---- .../moveit/robot_model/fixed_joint_model.h | 2 +- .../moveit/robot_model/floating_joint_model.h | 2 +- .../moveit/robot_model/joint_model_group.h | 6 ++-- .../include/moveit/robot_model/link_model.h | 2 +- .../moveit/robot_model/planar_joint_model.h | 2 +- .../robot_model/prismatic_joint_model.h | 2 +- .../moveit/robot_model/revolute_joint_model.h | 2 +- .../include/moveit/robot_model/robot_model.h | 16 +++++----- moveit_core/robot_model/src/aabb.cpp | 2 +- .../robot_model/src/fixed_joint_model.cpp | 2 +- .../robot_model/src/floating_joint_model.cpp | 2 +- moveit_core/robot_model/src/joint_model.cpp | 6 ++-- .../robot_model/src/joint_model_group.cpp | 8 ++--- moveit_core/robot_model/src/link_model.cpp | 6 ++-- .../robot_model/src/planar_joint_model.cpp | 2 +- .../robot_model/src/prismatic_joint_model.cpp | 2 +- .../robot_model/src/revolute_joint_model.cpp | 2 +- moveit_core/robot_model/src/robot_model.cpp | 2 +- moveit_core/robot_model/test/test.cpp | 4 +-- .../moveit/robot_state/attached_body.h | 4 +-- .../robot_state/cartesian_interpolator.h | 2 +- .../include/moveit/robot_state/conversions.h | 4 +-- .../include/moveit/robot_state/robot_state.h | 6 ++-- moveit_core/robot_state/src/attached_body.cpp | 2 +- .../src/cartesian_interpolator.cpp | 2 +- moveit_core/robot_state/src/conversions.cpp | 2 +- moveit_core/robot_state/src/robot_state.cpp | 10 +++---- .../test/robot_state_benchmark.cpp | 6 ++-- .../robot_state/test/robot_state_test.cpp | 6 ++-- moveit_core/robot_state/test/test_aabb.cpp | 8 ++--- .../test/test_cartesian_interpolator.cpp | 10 +++---- .../test/test_kinematic_complex.cpp | 8 ++--- .../robot_trajectory/robot_trajectory.h | 4 +-- .../robot_trajectory/src/robot_trajectory.cpp | 4 +-- .../test/test_robot_trajectory.cpp | 8 ++--- .../ruckig_traj_smoothing.h | 2 +- .../time_optimal_trajectory_generation.h | 4 +-- .../time_parameterization.h | 2 +- .../trajectory_processing/trajectory_tools.h | 4 +-- .../src/ruckig_traj_smoothing.cpp | 2 +- .../time_optimal_trajectory_generation.cpp | 2 +- .../src/trajectory_tools.cpp | 6 ++-- .../test/robot_trajectory_benchmark.cpp | 10 +++---- .../test/test_ruckig_traj_smoothing.cpp | 6 ++-- ...est_time_optimal_trajectory_generation.cpp | 4 +-- .../include/moveit/transforms/transforms.h | 2 +- moveit_core/transforms/src/transforms.cpp | 2 +- .../transforms/test/test_transforms.cpp | 2 +- .../moveit/utils/robot_model_test_utils.h | 2 +- moveit_core/utils/src/lexical_casts.cpp | 2 +- moveit_core/utils/src/message_checks.cpp | 2 +- moveit_core/utils/src/rclcpp_utils.cpp | 2 +- .../utils/src/robot_model_test_utils.cpp | 4 +-- moveit_core/version/CMakeLists.txt | 4 +-- moveit_core/version/version.cmake | 2 +- moveit_core/version/version.cpp | 2 +- .../version/{version.h.in => version.hpp.in} | 0 .../cached_ik_kinematics_plugin/README.md | 2 +- .../cached_ik_kinematics_plugin.h | 8 ++--- .../detail/NearestNeighborsGNAT.h | 2 +- .../src/cached_ik_kinematics_plugin.cpp | 6 ++-- .../src/ik_cache.cpp | 2 +- .../ikfast61_moveit_plugin_template.cpp | 4 +-- .../kdl_kinematics_plugin.h | 6 ++-- .../src/kdl_kinematics_plugin.cpp | 2 +- .../srv_kinematics_plugin.h | 4 +-- .../src/srv_kinematics_plugin.cpp | 4 +-- moveit_kinematics/test/benchmark_ik.cpp | 6 ++-- .../test/test_kinematics_plugin.cpp | 16 +++++----- .../chomp_interface/chomp_planning_context.h | 2 +- .../src/chomp_planning_context.cpp | 2 +- .../chomp_interface/src/chomp_plugin.cpp | 8 ++--- .../test/chomp_moveit_test_panda.cpp | 4 +-- .../test/chomp_moveit_test_rrbot.cpp | 4 +-- .../chomp_motion_planner/chomp_optimizer.h | 6 ++-- .../chomp_motion_planner/chomp_planner.h | 8 ++--- .../chomp_motion_planner/chomp_trajectory.h | 2 +- .../chomp_motion_planner/chomp_utils.h | 2 +- .../src/chomp_optimizer.cpp | 6 ++-- .../src/chomp_planner.cpp | 2 +- .../detail/constrained_goal_sampler.h | 8 ++--- .../detail/constrained_sampler.h | 2 +- .../detail/constraint_approximations.h | 6 ++-- .../detail/constraints_library.h | 8 ++--- .../ompl_interface/detail/ompl_constraints.h | 6 ++-- .../detail/projection_evaluators.h | 2 +- .../detail/state_validity_checker.h | 6 ++-- .../detail/threadsafe_state_storage.h | 2 +- .../model_based_planning_context.h | 6 ++-- .../moveit/ompl_interface/ompl_interface.h | 8 ++--- .../constrained_planning_state_space.h | 4 +-- ...constrained_planning_state_space_factory.h | 2 +- .../joint_space/joint_model_state_space.h | 2 +- .../joint_model_state_space_factory.h | 2 +- .../model_based_state_space.h | 8 ++--- .../model_based_state_space_factory.h | 4 +-- .../work_space/pose_model_state_space.h | 2 +- .../pose_model_state_space_factory.h | 2 +- .../ompl_interface/planning_context_manager.h | 8 ++--- .../scripts/generate_state_database.cpp | 14 ++++----- .../src/detail/constrained_goal_sampler.cpp | 6 ++-- .../src/detail/constrained_sampler.cpp | 4 +-- .../src/detail/constraints_library.cpp | 4 +-- .../ompl_interface/src/detail/goal_union.cpp | 2 +- .../src/detail/ompl_constraints.cpp | 2 +- .../src/detail/projection_evaluators.cpp | 6 ++-- .../src/detail/state_validity_checker.cpp | 4 +-- .../src/detail/threadsafe_state_storage.cpp | 2 +- .../src/model_based_planning_context.cpp | 18 +++++------ .../ompl_interface/src/ompl_interface.cpp | 8 ++--- .../src/ompl_planner_manager.cpp | 6 ++-- .../constrained_planning_state_space.cpp | 2 +- ...nstrained_planning_state_space_factory.cpp | 4 +-- .../joint_space/joint_model_state_space.cpp | 2 +- .../joint_model_state_space_factory.cpp | 4 +-- .../model_based_state_space.cpp | 2 +- .../model_based_state_space_factory.cpp | 2 +- .../work_space/pose_model_state_space.cpp | 2 +- .../pose_model_state_space_factory.cpp | 4 +-- .../src/planning_context_manager.cpp | 16 +++++----- .../ompl_interface/test/load_test_robot.h | 8 ++--- .../test_constrained_planning_state_space.cpp | 10 +++---- ...est_constrained_state_validity_checker.cpp | 10 +++---- .../test/test_ompl_constraints.cpp | 10 +++---- .../test/test_planning_context_manager.cpp | 16 +++++----- .../ompl_interface/test/test_state_space.cpp | 8 ++--- .../test/test_state_validity_checker.cpp | 8 ++--- .../test/test_threadsafe_state_storage.cpp | 2 +- .../command_list_manager.h | 10 +++---- .../joint_limits_aggregator.h | 10 +++---- .../joint_limits_container.h | 2 +- .../joint_limits_interface_extension.h | 2 +- .../joint_limits_validator.h | 4 +-- .../limits_container.h | 2 +- .../move_group_sequence_action.h | 2 +- .../move_group_sequence_service.h | 2 +- .../pilz_industrial_motion_planner.h | 8 ++--- .../plan_components_builder.h | 16 +++++----- .../planning_context_base.h | 12 ++++---- .../planning_context_circ.h | 10 +++---- .../planning_context_lin.h | 10 +++---- .../planning_context_loader.h | 6 ++-- .../planning_context_loader_circ.h | 4 +-- .../planning_context_loader_lin.h | 4 +-- .../planning_context_loader_ptp.h | 4 +-- .../planning_context_ptp.h | 10 +++---- .../tip_frame_getter.h | 2 +- .../trajectory_blend_request.h | 2 +- .../trajectory_blend_response.h | 2 +- .../trajectory_blender.h | 10 +++---- .../trajectory_blender_transition_window.h | 12 ++++---- .../trajectory_functions.h | 14 ++++----- .../trajectory_generator.h | 16 +++++----- .../trajectory_generator_circ.h | 4 +-- .../trajectory_generator_lin.h | 6 ++-- .../trajectory_generator_ptp.h | 8 ++--- .../src/command_list_manager.cpp | 14 ++++----- .../src/joint_limits_aggregator.cpp | 8 ++--- .../src/joint_limits_container.cpp | 2 +- .../src/joint_limits_validator.cpp | 10 +++---- .../src/limits_container.cpp | 2 +- .../src/move_group_sequence_action.cpp | 20 ++++++------- .../src/move_group_sequence_service.cpp | 10 +++---- .../src/path_circle_generator.cpp | 2 +- .../src/pilz_industrial_motion_planner.cpp | 10 +++---- .../src/plan_components_builder.cpp | 4 +-- .../src/planning_context_loader.cpp | 2 +- .../src/planning_context_loader_circ.cpp | 8 ++--- .../src/planning_context_loader_lin.cpp | 8 ++--- .../src/planning_context_loader_ptp.cpp | 6 ++-- .../trajectory_blender_transition_window.cpp | 4 +-- .../src/trajectory_functions.cpp | 4 +-- .../src/trajectory_generator.cpp | 6 ++-- .../src/trajectory_generator_circ.cpp | 6 ++-- .../src/trajectory_generator_lin.cpp | 6 ++-- .../src/trajectory_generator_ptp.cpp | 4 +-- .../src/velocity_profile_atrap.cpp | 2 +- .../integrationtest_command_list_manager.cpp | 18 +++++------ .../src/integrationtest_command_planning.cpp | 12 ++++---- .../integrationtest_get_solver_tip_frame.cpp | 8 ++--- ...ntegrationtest_plan_components_builder.cpp | 8 ++--- .../src/integrationtest_sequence_action.cpp | 16 +++++----- ...grationtest_sequence_action_preemption.cpp | 16 +++++----- ...rationtest_sequence_service_capability.cpp | 14 ++++----- .../test/test_utils.cpp | 4 +-- .../test/test_utils.h | 14 ++++----- .../src/unittest_get_solver_tip_frame.cpp | 4 +-- .../unit_tests/src/unittest_joint_limit.cpp | 4 +-- .../src/unittest_joint_limits_aggregator.cpp | 10 +++---- .../src/unittest_joint_limits_container.cpp | 4 +-- .../src/unittest_joint_limits_validator.cpp | 4 +-- ...nittest_pilz_industrial_motion_planner.cpp | 6 ++-- ..._pilz_industrial_motion_planner_direct.cpp | 6 ++-- .../src/unittest_planning_context.cpp | 18 +++++------ .../src/unittest_planning_context_loaders.cpp | 6 ++-- ...t_trajectory_blender_transition_window.cpp | 24 +++++++-------- .../src/unittest_trajectory_functions.cpp | 16 +++++----- .../src/unittest_trajectory_generator.cpp | 2 +- .../unittest_trajectory_generator_circ.cpp | 16 +++++----- .../unittest_trajectory_generator_common.cpp | 30 +++++++++---------- .../src/unittest_trajectory_generator_lin.cpp | 18 +++++------ .../src/unittest_velocity_profile_atrap.cpp | 2 +- .../cartesianconfiguration.h | 8 ++--- .../checks.h | 2 +- .../goalconstraintsmsgconvertible.h | 2 +- .../interim.h | 2 +- .../jointconfiguration.h | 6 ++-- .../lin.h | 2 +- .../motioncmd.h | 2 +- .../motionplanrequestconvertible.h | 4 +-- .../ptp.h | 2 +- .../robotconfiguration.h | 6 ++-- .../robotstatemsgconvertible.h | 2 +- .../sequence.h | 4 +-- .../testdata_loader.h | 12 ++++---- .../xml_testdata_loader.h | 2 +- .../src/cartesianconfiguration.cpp | 2 +- .../src/jointconfiguration.cpp | 4 +-- .../src/robotconfiguration.cpp | 2 +- .../src/sequence.cpp | 2 +- .../src/xml_testdata_loader.cpp | 8 ++--- .../stomp_moveit/conversion_functions.hpp | 4 +-- .../include/stomp_moveit/cost_functions.hpp | 4 +-- .../include/stomp_moveit/filter_functions.hpp | 2 +- .../stomp_moveit_planning_context.hpp | 2 +- .../stomp_moveit/trajectory_visualization.hpp | 4 +-- .../src/stomp_moveit_planning_context.cpp | 4 +-- .../src/prbt_manipulator_ikfast_solver.cpp | 2 +- .../ControllerHandle.h | 4 +-- .../src/controller_manager_plugin.cpp | 8 ++--- .../src/empty_controller_plugin.cpp | 2 +- .../src/gripper_controller_plugin.cpp | 4 +-- .../joint_trajectory_controller_plugin.cpp | 4 +-- .../action_based_controller_handle.h | 4 +-- .../empty_controller_handle.h | 2 +- ...ollow_joint_trajectory_controller_handle.h | 2 +- .../gripper_controller_handle.h | 2 +- ...low_joint_trajectory_controller_handle.cpp | 2 +- .../src/moveit_simple_controller_manager.cpp | 6 ++-- moveit_py/src/moveit/core.cpp | 24 +++++++-------- .../collision_detection/collision_common.cpp | 2 +- .../collision_detection/collision_common.h | 2 +- .../collision_detection/collision_matrix.cpp | 2 +- .../collision_detection/collision_matrix.h | 2 +- .../moveit_core/collision_detection/world.cpp | 2 +- .../moveit_core/collision_detection/world.h | 2 +- .../controller_manager/controller_manager.cpp | 2 +- .../controller_manager/controller_manager.h | 2 +- .../kinematic_constraints/utils.cpp | 6 ++-- .../moveit_core/kinematic_constraints/utils.h | 2 +- .../planning_interface/planning_response.cpp | 2 +- .../planning_interface/planning_response.h | 8 ++--- .../planning_scene/planning_scene.cpp | 4 +-- .../planning_scene/planning_scene.h | 6 ++-- .../moveit_core/robot_model/joint_model.cpp | 4 +-- .../moveit_core/robot_model/joint_model.h | 2 +- .../robot_model/joint_model_group.cpp | 2 +- .../robot_model/joint_model_group.h | 2 +- .../moveit_core/robot_model/robot_model.cpp | 4 +-- .../moveit_core/robot_state/robot_state.cpp | 6 ++-- .../moveit_core/robot_state/robot_state.h | 4 +-- .../robot_trajectory/robot_trajectory.cpp | 6 ++-- .../robot_trajectory/robot_trajectory.h | 2 +- .../moveit_core/transforms/transforms.cpp | 2 +- .../moveit_core/transforms/transforms.h | 2 +- .../moveit_py_utils/src/copy_ros_msg.cpp | 2 +- .../src/ros_msg_typecasters.cpp | 2 +- .../moveit/moveit_ros/moveit_cpp/moveit_cpp.h | 10 +++---- .../moveit_cpp/planning_component.cpp | 2 +- .../moveit_cpp/planning_component.h | 14 ++++----- .../planning_scene_monitor.cpp | 2 +- .../planning_scene_monitor.h | 6 ++-- .../trajectory_execution_manager.cpp | 2 +- .../trajectory_execution_manager.h | 6 ++-- moveit_py/src/moveit/planning.cpp | 8 ++--- .../moveit/benchmarks/BenchmarkExecutor.h | 18 +++++------ .../benchmarks/src/BenchmarkExecutor.cpp | 12 ++++---- .../benchmarks/src/BenchmarkOptions.cpp | 2 +- moveit_ros/benchmarks/src/RunBenchmark.cpp | 4 +-- .../global_planner/global_planner_component.h | 2 +- .../global_planner/global_planner_interface.h | 2 +- .../src/global_planner_component.cpp | 6 ++-- .../global_planner/moveit_planning_pipeline.h | 6 ++-- .../src/moveit_planning_pipeline.cpp | 6 ++-- .../hybrid_planning_manager.h | 2 +- .../planner_logic_interface.h | 4 +-- .../src/hybrid_planning_manager.cpp | 4 +-- .../replan_invalidated_trajectory.h | 2 +- .../single_plan_execution.h | 4 +-- .../src/replan_invalidated_trajectory.cpp | 4 +-- .../src/single_plan_execution.cpp | 2 +- .../forward_trajectory.h | 2 +- .../src/forward_trajectory.cpp | 8 ++--- .../local_constraint_solver_interface.h | 4 +-- .../local_planner/local_planner_component.h | 8 ++--- .../trajectory_operator_interface.h | 4 +-- .../src/local_planner_component.cpp | 8 ++--- .../simple_sampler.h | 4 +-- .../src/simple_sampler.cpp | 4 +-- .../test/test_basic_integration.cpp | 8 ++--- .../moveit/move_group/move_group_capability.h | 10 +++---- .../moveit/move_group/move_group_context.h | 2 +- ...pply_planning_scene_service_capability.cpp | 6 ++-- .../apply_planning_scene_service_capability.h | 2 +- .../cartesian_path_service_capability.cpp | 20 ++++++------- .../cartesian_path_service_capability.h | 2 +- .../clear_octomap_service_capability.cpp | 6 ++-- .../clear_octomap_service_capability.h | 2 +- .../execute_trajectory_action_capability.cpp | 12 ++++---- .../execute_trajectory_action_capability.h | 2 +- .../get_group_urdf_capability.cpp | 6 ++-- .../get_group_urdf_capability.h | 2 +- .../get_planning_scene_service_capability.cpp | 4 +-- .../get_planning_scene_service_capability.h | 2 +- .../kinematics_service_capability.cpp | 10 +++---- .../kinematics_service_capability.h | 2 +- ..._geometry_from_file_service_capability.cpp | 6 ++-- ...ad_geometry_from_file_service_capability.h | 2 +- .../move_action_capability.cpp | 18 +++++------ .../move_action_capability.h | 2 +- .../plan_service_capability.cpp | 8 ++--- .../plan_service_capability.h | 2 +- .../query_planners_service_capability.cpp | 8 ++--- .../query_planners_service_capability.h | 2 +- ...ve_geometry_to_file_service_capability.cpp | 6 ++-- ...save_geometry_to_file_service_capability.h | 2 +- .../state_validation_service_capability.cpp | 12 ++++---- .../state_validation_service_capability.h | 2 +- .../tf_publisher_capability.cpp | 14 ++++----- .../tf_publisher_capability.h | 2 +- .../move_group/src/list_capabilities.cpp | 2 +- moveit_ros/move_group/src/move_group.cpp | 12 ++++---- .../move_group/src/move_group_capability.cpp | 8 ++--- .../move_group/src/move_group_context.cpp | 8 ++--- .../demos/cpp_interface/demo_pose.cpp | 2 +- .../demos/cpp_interface/demo_twist.cpp | 2 +- .../moveit_servo/collision_monitor.hpp | 4 +-- .../include/moveit_servo/servo.hpp | 8 ++--- .../include/moveit_servo/utils/command.hpp | 4 +-- .../include/moveit_servo/utils/common.hpp | 6 ++-- moveit_ros/moveit_servo/tests/test_utils.cpp | 2 +- .../occupancy_map_monitor.h | 4 +-- ...ccupancy_map_monitor_middleware_handle.hpp | 4 +-- .../occupancy_map_updater.h | 4 +-- .../src/occupancy_map_monitor.cpp | 4 +-- ...ccupancy_map_monitor_middleware_handle.cpp | 2 +- .../src/occupancy_map_server.cpp | 2 +- .../src/occupancy_map_updater.cpp | 4 +-- .../test/occupancy_map_monitor_tests.cpp | 2 +- .../depth_image_octomap_updater.h | 8 ++--- .../src/depth_image_octomap_updater.cpp | 4 +-- .../include/moveit/mesh_filter/filter_job.h | 2 +- .../include/moveit/mesh_filter/gl_renderer.h | 2 +- .../include/moveit/mesh_filter/sensor_model.h | 2 +- .../moveit/mesh_filter/transform_provider.h | 6 ++-- .../src/depth_self_filter_nodelet.cpp | 10 +++---- .../perception/mesh_filter/src/gl_mesh.cpp | 2 +- .../mesh_filter/src/gl_renderer.cpp | 2 +- .../mesh_filter/src/mesh_filter.cpp | 4 +-- .../mesh_filter/src/mesh_filter_base.cpp | 6 ++-- .../mesh_filter/src/sensor_model.cpp | 2 +- .../mesh_filter/src/stereo_camera_model.cpp | 4 +-- .../mesh_filter/test/mesh_filter_test.cpp | 4 +-- .../src/shape_mask.cpp | 2 +- .../pointcloud_octomap_updater.h | 4 +-- .../src/plugin_init.cpp | 2 +- .../src/pointcloud_octomap_updater.cpp | 4 +-- .../semantic_world/src/semantic_world.cpp | 2 +- .../collision_plugin_loader.h | 2 +- .../src/collision_plugin_loader.cpp | 2 +- .../constraint_sampler_manager_loader.h | 4 +-- .../src/constraint_sampler_manager_loader.cpp | 2 +- .../kinematics_plugin_loader.h | 6 ++-- .../src/kinematics_plugin_loader.cpp | 4 +-- .../include/moveit/moveit_cpp/moveit_cpp.h | 10 +++---- .../moveit/plan_execution/plan_execution.h | 10 +++---- .../plan_execution/plan_representation.h | 4 +-- .../plan_execution/src/plan_execution.cpp | 14 ++++----- .../src/display_random_state.cpp | 2 +- .../src/evaluate_collision_checking_speed.cpp | 2 +- .../src/print_planning_model_info.cpp | 2 +- .../src/print_planning_scene_info.cpp | 2 +- .../src/publish_scene_from_text.cpp | 2 +- .../src/visualize_robot_collision_volume.cpp | 2 +- .../planning_pipeline/planning_pipeline.h | 8 ++--- .../src/planning_pipeline.cpp | 2 +- .../test/planning_pipeline_test_plugins.cpp | 6 ++-- .../test/planning_pipeline_tests.cpp | 4 +-- .../plan_responses_container.hpp | 4 +-- .../planning_pipeline_interfaces.hpp | 8 ++--- .../src/check_for_stacked_constraints.cpp | 2 +- .../src/check_start_state_bounds.cpp | 6 ++-- .../src/check_start_state_collision.cpp | 6 ++-- .../src/resolve_constraint_frames.cpp | 4 +-- .../src/validate_workspace_bounds.cpp | 2 +- .../src/add_ruckig_traj_smoothing.cpp | 4 +-- .../src/add_time_optimal_parameterization.cpp | 4 +-- .../src/display_motion_path.cpp | 4 +-- .../src/validate_path.cpp | 4 +-- .../demos/demo_scene.cpp | 2 +- .../current_state_monitor.h | 2 +- ...urrent_state_monitor_middleware_handle.hpp | 2 +- .../planning_scene_monitor.h | 14 ++++----- .../trajectory_monitor.h | 8 ++--- .../trajectory_monitor_middleware_handle.hpp | 2 +- .../src/current_state_monitor.cpp | 2 +- .../src/planning_scene_monitor.cpp | 8 ++--- .../src/trajectory_monitor.cpp | 4 +-- .../test/current_state_monitor_tests.cpp | 4 +-- .../test/planning_scene_monitor_test.cpp | 4 +-- .../test/trajectory_monitor_tests.cpp | 6 ++-- .../include/moveit/rdf_loader/rdf_loader.h | 4 +-- .../planning/rdf_loader/src/rdf_loader.cpp | 2 +- .../src/synchronized_string_parameter.cpp | 2 +- .../rdf_loader/test/test_rdf_integration.cpp | 2 +- .../robot_model_loader/robot_model_loader.h | 8 ++--- .../src/robot_model_loader.cpp | 2 +- .../trajectory_execution_manager.h | 10 +++---- .../src/trajectory_execution_manager.cpp | 6 ++-- .../test/test_execution_manager.cpp | 4 +-- .../test/test_moveit_controller_manager.h | 2 +- .../test_moveit_controller_manager_plugin.cpp | 2 +- .../common_objects.h | 4 +-- .../src/common_objects.cpp | 2 +- .../move_group_interface.h | 8 ++--- .../src/planning_scene_interface.cpp | 4 +-- .../test/move_group_interface_cpp_test.cpp | 8 ++--- .../test/move_group_ompl_constraints_test.cpp | 6 ++-- .../trajectory_cache/src/trajectory_cache.cpp | 2 +- .../motion_planning_frame_joints_widget.h | 4 +-- .../src/motion_planning_frame.cpp | 12 ++++---- .../src/robot_state_display.cpp | 6 ++-- .../planning_link_updater.h | 2 +- .../rviz_plugin_render_tools/render_shapes.h | 4 +-- .../src/render_shapes.cpp | 4 +-- .../src/robot_state_visualization.cpp | 6 ++-- .../src/trajectory_panel.cpp | 2 +- .../src/trajectory_visualization.cpp | 8 ++--- .../trajectory_display.h | 4 +-- .../src/plugin_init.cpp | 2 +- .../src/trajectory_display.cpp | 2 +- .../moveit/warehouse/constraints_storage.h | 6 ++-- .../moveit/warehouse/moveit_message_storage.h | 2 +- .../moveit/warehouse/planning_scene_storage.h | 6 ++-- .../warehouse/planning_scene_world_storage.h | 2 +- .../include/moveit/warehouse/state_storage.h | 6 ++-- .../trajectory_constraints_storage.h | 4 +-- moveit_ros/warehouse/src/broadcast.cpp | 6 ++-- .../warehouse/src/constraints_storage.cpp | 2 +- moveit_ros/warehouse/src/import_from_text.cpp | 12 ++++---- .../warehouse/src/initialize_demo_db.cpp | 12 ++++---- .../warehouse/src/moveit_message_storage.cpp | 4 +-- .../warehouse/src/planning_scene_storage.cpp | 2 +- .../src/planning_scene_world_storage.cpp | 2 +- moveit_ros/warehouse/src/save_as_text.cpp | 10 +++---- .../warehouse/src/save_to_warehouse.cpp | 8 ++--- moveit_ros/warehouse/src/state_storage.cpp | 2 +- .../src/trajectory_constraints_storage.cpp | 2 +- .../warehouse/src/warehouse_connector.cpp | 2 +- .../warehouse/src/warehouse_services.cpp | 2 +- .../src/collisions_updater.cpp | 2 +- .../src/controllers_widget.cpp | 2 +- .../include/moveit_setup_framework/config.hpp | 2 +- .../data/srdf_config.hpp | 6 ++-- .../moveit_setup_framework/data_warehouse.hpp | 2 +- .../moveit_setup_framework/generated_file.hpp | 2 +- .../moveit_setup_framework/qt/rviz_panel.hpp | 2 +- .../src/srdf_config.cpp | 2 +- .../src/urdf_config.cpp | 2 +- .../src/simulation_widget.cpp | 2 +- .../compute_default_collisions.hpp | 2 +- .../planning_groups.hpp | 2 +- .../src/compute_default_collisions.cpp | 2 +- .../src/planning_groups.cpp | 2 +- .../src/robot_poses.cpp | 2 +- 601 files changed, 1531 insertions(+), 1529 deletions(-) rename moveit_core/version/{version.h.in => version.hpp.in} (100%) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h index 316497e9cf..ccb95c0269 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h @@ -36,10 +36,10 @@ #pragma once -#include -#include +#include +#include -#include +#include namespace collision_detection { diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h index 50b543d837..7615ca55ba 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h @@ -36,7 +36,7 @@ #pragma once -#include +#include namespace collision_detection { diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h index db246518fd..49d12da47d 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h @@ -43,7 +43,7 @@ #include #include #include -#include +#include namespace collision_detection { diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h index d63bb5aaff..d9ece9f39f 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include namespace collision_detection { diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h index c846274021..b05ad97cb9 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h @@ -36,12 +36,12 @@ #pragma once -#include -#include -#include +#include +#include +#include #include #include -#include +#include namespace collision_detection { diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h index 1192ff87f6..fff68a3142 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include #include #include #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h index 36069f95a5..1316d23c4b 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include namespace collision_detection { diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h index 226d4e4f8c..afc032700a 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h @@ -34,9 +34,9 @@ #pragma once -#include -#include -#include +#include +#include +#include namespace collision_detection { diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h index 05c539854b..f692448516 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h @@ -34,8 +34,8 @@ #pragma once -#include -#include +#include +#include namespace collision_detection { diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h index 61caac8646..f55f01e35c 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h @@ -36,7 +36,7 @@ #pragma once -#include +#include #include #include #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h index 061a304085..6fb1a5e934 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h @@ -34,15 +34,15 @@ /* Author: Jens Petit */ -#include -#include -#include -#include -#include -#include - -#include -#include +#include +#include +#include +#include +#include +#include + +#include +#include #include #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h index 660ee09012..5b7c668dff 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h @@ -34,13 +34,13 @@ /* Author: E. Gil Jones */ -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include #include #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/world.h b/moveit_core/collision_detection/include/moveit/collision_detection/world.h index d610d4b43c..a3f41643b3 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/world.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/world.h @@ -36,14 +36,14 @@ #pragma once -#include +#include #include #include #include #include #include #include -#include +#include namespace shapes { diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h b/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h index eed71965cc..7e35a692a5 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include namespace collision_detection { diff --git a/moveit_core/collision_detection/src/allvalid/collision_env_allvalid.cpp b/moveit_core/collision_detection/src/allvalid/collision_env_allvalid.cpp index 2605289cab..917c7f7fc8 100644 --- a/moveit_core/collision_detection/src/allvalid/collision_env_allvalid.cpp +++ b/moveit_core/collision_detection/src/allvalid/collision_env_allvalid.cpp @@ -34,8 +34,8 @@ /* Author: Ioan Sucan, Jia Pan, Jens Petit */ -#include -#include +#include +#include #include #include #include diff --git a/moveit_core/collision_detection/src/collision_common.cpp b/moveit_core/collision_detection/src/collision_common.cpp index 8ee2090959..d956756aad 100644 --- a/moveit_core/collision_detection/src/collision_common.cpp +++ b/moveit_core/collision_detection/src/collision_common.cpp @@ -32,7 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include #include #include #include diff --git a/moveit_core/collision_detection/src/collision_env.cpp b/moveit_core/collision_detection/src/collision_env.cpp index a353ec54cc..2b065fc0eb 100644 --- a/moveit_core/collision_detection/src/collision_env.cpp +++ b/moveit_core/collision_detection/src/collision_env.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan, Jens Petit */ -#include +#include #include #include #include diff --git a/moveit_core/collision_detection/src/collision_matrix.cpp b/moveit_core/collision_detection/src/collision_matrix.cpp index eb2ef1fa1a..61950548b6 100644 --- a/moveit_core/collision_detection/src/collision_matrix.cpp +++ b/moveit_core/collision_detection/src/collision_matrix.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan, E. Gil Jones */ -#include +#include #include #include #include diff --git a/moveit_core/collision_detection/src/collision_octomap_filter.cpp b/moveit_core/collision_detection/src/collision_octomap_filter.cpp index aca52fa2c8..1dc1688d22 100644 --- a/moveit_core/collision_detection/src/collision_octomap_filter.cpp +++ b/moveit_core/collision_detection/src/collision_octomap_filter.cpp @@ -34,8 +34,8 @@ /* Author: Adam Leeper */ -#include -#include +#include +#include #include #include #include diff --git a/moveit_core/collision_detection/src/collision_plugin_cache.cpp b/moveit_core/collision_detection/src/collision_plugin_cache.cpp index 619bece8f4..adba5a3988 100644 --- a/moveit_core/collision_detection/src/collision_plugin_cache.cpp +++ b/moveit_core/collision_detection/src/collision_plugin_cache.cpp @@ -32,7 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include #include #include #include diff --git a/moveit_core/collision_detection/src/collision_tools.cpp b/moveit_core/collision_detection/src/collision_tools.cpp index eaef0dbc8b..e9b69bf05a 100644 --- a/moveit_core/collision_detection/src/collision_tools.cpp +++ b/moveit_core/collision_detection/src/collision_tools.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include +#include #include #include #include diff --git a/moveit_core/collision_detection/src/world.cpp b/moveit_core/collision_detection/src/world.cpp index ce7c6006fc..57e7315a40 100644 --- a/moveit_core/collision_detection/src/world.cpp +++ b/moveit_core/collision_detection/src/world.cpp @@ -34,8 +34,8 @@ /* Author: Acorn Pooley, Ioan Sucan */ -#include -#include +#include +#include #include #include #include diff --git a/moveit_core/collision_detection/src/world_diff.cpp b/moveit_core/collision_detection/src/world_diff.cpp index d5f8e65978..a58c5cebea 100644 --- a/moveit_core/collision_detection/src/world_diff.cpp +++ b/moveit_core/collision_detection/src/world_diff.cpp @@ -34,7 +34,7 @@ /* Author: Acorn Pooley, Ioan Sucan */ -#include +#include #include namespace collision_detection diff --git a/moveit_core/collision_detection/test/test_all_valid.cpp b/moveit_core/collision_detection/test/test_all_valid.cpp index 664d0e74cf..d16eb4dca4 100644 --- a/moveit_core/collision_detection/test/test_all_valid.cpp +++ b/moveit_core/collision_detection/test/test_all_valid.cpp @@ -35,8 +35,8 @@ /* Author: Simon Schmeisser */ #include -#include -#include +#include +#include TEST(AllValid, Instantiate) { diff --git a/moveit_core/collision_detection/test/test_world.cpp b/moveit_core/collision_detection/test/test_world.cpp index f2d2c09227..6ce68439ea 100644 --- a/moveit_core/collision_detection/test/test_world.cpp +++ b/moveit_core/collision_detection/test/test_world.cpp @@ -35,7 +35,7 @@ /* Author: Acorn Pooley */ #include -#include +#include #include #include diff --git a/moveit_core/collision_detection/test/test_world_diff.cpp b/moveit_core/collision_detection/test/test_world_diff.cpp index e073cb17c1..c87cb9396f 100644 --- a/moveit_core/collision_detection/test/test_world_diff.cpp +++ b/moveit_core/collision_detection/test/test_world_diff.cpp @@ -35,7 +35,7 @@ /* Author: Acorn Pooley */ #include -#include +#include #include TEST(WorldDiff, TrackChanges) diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h index d243c030be..b9dd53a8c9 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h @@ -29,7 +29,7 @@ #include #include #include -#include +#include namespace collision_detection_bullet { diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h index 946fd81125..04f9fe5921 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h @@ -33,8 +33,8 @@ #pragma once -#include -#include +#include +#include namespace collision_detection_bullet { diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h index 5435c6419d..3cc0192305 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h @@ -33,9 +33,9 @@ #pragma once -#include -#include -#include +#include +#include +#include namespace collision_detection_bullet { diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h index d4e0d8b9e0..b9cca6d865 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h @@ -33,9 +33,9 @@ #pragma once -#include -#include -#include +#include +#include +#include namespace collision_detection_bullet { diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h index 676e2f4eb8..6bacd5718b 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h @@ -38,11 +38,11 @@ #include #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include namespace collision_detection_bullet { diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h index b54bee4bb1..1784da1f13 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h @@ -25,9 +25,9 @@ #include #include -#include -#include -#include +#include +#include +#include namespace collision_detection_bullet { diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h index 9a9f4859ea..c97e799ea5 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h @@ -28,7 +28,7 @@ #include #include -#include +#include namespace collision_detection_bullet { diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h index ed608502b9..c703727022 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h @@ -36,10 +36,10 @@ #pragma once -#include -#include +#include +#include -#include +#include namespace collision_detection { diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h index 1453e09049..fd06e39782 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include namespace collision_detection { diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h index 7854022874..953686bd95 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h @@ -36,9 +36,9 @@ #pragma once -#include -#include -#include +#include +#include +#include #include namespace collision_detection diff --git a/moveit_core/collision_detection_bullet/src/bullet_integration/bullet_bvh_manager.cpp b/moveit_core/collision_detection_bullet/src/bullet_integration/bullet_bvh_manager.cpp index e9af94b015..2883f264d8 100644 --- a/moveit_core/collision_detection_bullet/src/bullet_integration/bullet_bvh_manager.cpp +++ b/moveit_core/collision_detection_bullet/src/bullet_integration/bullet_bvh_manager.cpp @@ -31,7 +31,7 @@ /* Authors: Levi Armstrong, Jens Petit */ -#include +#include #include #include diff --git a/moveit_core/collision_detection_bullet/src/bullet_integration/bullet_cast_bvh_manager.cpp b/moveit_core/collision_detection_bullet/src/bullet_integration/bullet_cast_bvh_manager.cpp index e7153a2b16..533782ed4b 100644 --- a/moveit_core/collision_detection_bullet/src/bullet_integration/bullet_cast_bvh_manager.cpp +++ b/moveit_core/collision_detection_bullet/src/bullet_integration/bullet_cast_bvh_manager.cpp @@ -31,13 +31,13 @@ /* Author: Levi Armstrong, Jens Petit */ -#include +#include #include #include #include #include -#include +#include namespace collision_detection_bullet { diff --git a/moveit_core/collision_detection_bullet/src/bullet_integration/bullet_discrete_bvh_manager.cpp b/moveit_core/collision_detection_bullet/src/bullet_integration/bullet_discrete_bvh_manager.cpp index 29f56f3b3b..780cd74e22 100644 --- a/moveit_core/collision_detection_bullet/src/bullet_integration/bullet_discrete_bvh_manager.cpp +++ b/moveit_core/collision_detection_bullet/src/bullet_integration/bullet_discrete_bvh_manager.cpp @@ -31,11 +31,11 @@ /* Author: Levi Armstrong, Jens Petit */ -#include +#include #include #include -#include +#include namespace collision_detection_bullet { diff --git a/moveit_core/collision_detection_bullet/src/bullet_integration/bullet_utils.cpp b/moveit_core/collision_detection_bullet/src/bullet_integration/bullet_utils.cpp index 3fe31c3824..45a8952f13 100644 --- a/moveit_core/collision_detection_bullet/src/bullet_integration/bullet_utils.cpp +++ b/moveit_core/collision_detection_bullet/src/bullet_integration/bullet_utils.cpp @@ -32,7 +32,7 @@ /* Authors: John Schulman, Levi Armstrong */ -#include +#include #include #include @@ -42,7 +42,7 @@ #include #include #include -#include +#include namespace collision_detection_bullet { diff --git a/moveit_core/collision_detection_bullet/src/bullet_integration/contact_checker_common.cpp b/moveit_core/collision_detection_bullet/src/bullet_integration/contact_checker_common.cpp index 4da803358e..f0bffc58f4 100644 --- a/moveit_core/collision_detection_bullet/src/bullet_integration/contact_checker_common.cpp +++ b/moveit_core/collision_detection_bullet/src/bullet_integration/contact_checker_common.cpp @@ -33,11 +33,11 @@ * Author: Levi Armstrong */ -#include +#include #include #include -#include +#include namespace collision_detection_bullet { diff --git a/moveit_core/collision_detection_bullet/src/bullet_integration/ros_bullet_utils.cpp b/moveit_core/collision_detection_bullet/src/bullet_integration/ros_bullet_utils.cpp index b326780991..2e308bfbd2 100644 --- a/moveit_core/collision_detection_bullet/src/bullet_integration/ros_bullet_utils.cpp +++ b/moveit_core/collision_detection_bullet/src/bullet_integration/ros_bullet_utils.cpp @@ -31,7 +31,7 @@ /* Author: Jorge Nicho*/ -#include +#include #include #include diff --git a/moveit_core/collision_detection_bullet/src/collision_detector_bullet_plugin_loader.cpp b/moveit_core/collision_detection_bullet/src/collision_detector_bullet_plugin_loader.cpp index 5e319499f5..ba85581a27 100644 --- a/moveit_core/collision_detection_bullet/src/collision_detector_bullet_plugin_loader.cpp +++ b/moveit_core/collision_detection_bullet/src/collision_detector_bullet_plugin_loader.cpp @@ -34,7 +34,7 @@ /* Author: Jens Petit */ -#include +#include #include namespace collision_detection diff --git a/moveit_core/collision_detection_bullet/src/collision_env_bullet.cpp b/moveit_core/collision_detection_bullet/src/collision_env_bullet.cpp index 873dfb0a21..37210fe66d 100644 --- a/moveit_core/collision_detection_bullet/src/collision_env_bullet.cpp +++ b/moveit_core/collision_detection_bullet/src/collision_env_bullet.cpp @@ -34,10 +34,10 @@ /* Author: Jens Petit */ -#include -#include -#include -#include +#include +#include +#include +#include #include #include #include diff --git a/moveit_core/collision_detection_bullet/test/test_bullet_collision_detection_panda.cpp b/moveit_core/collision_detection_bullet/test/test_bullet_collision_detection_panda.cpp index 1e164b33f7..209b5bfcb1 100644 --- a/moveit_core/collision_detection_bullet/test/test_bullet_collision_detection_panda.cpp +++ b/moveit_core/collision_detection_bullet/test/test_bullet_collision_detection_panda.cpp @@ -34,8 +34,8 @@ /* Author: Jens Petit */ -#include -#include +#include +#include INSTANTIATE_TYPED_TEST_SUITE_P(BulletCollisionCheckPanda, CollisionDetectorPandaTest, collision_detection::CollisionDetectorAllocatorBullet); diff --git a/moveit_core/collision_detection_bullet/test/test_bullet_collision_detection_pr2.cpp b/moveit_core/collision_detection_bullet/test/test_bullet_collision_detection_pr2.cpp index 997d73b689..4b69a4d17d 100644 --- a/moveit_core/collision_detection_bullet/test/test_bullet_collision_detection_pr2.cpp +++ b/moveit_core/collision_detection_bullet/test/test_bullet_collision_detection_pr2.cpp @@ -34,8 +34,8 @@ /* Author: Jens Petit */ -#include -#include +#include +#include INSTANTIATE_TYPED_TEST_SUITE_P(BulletCollisionCheck, CollisionDetectorTest, collision_detection::CollisionDetectorAllocatorBullet); diff --git a/moveit_core/collision_detection_bullet/test/test_bullet_continuous_collision_checking.cpp b/moveit_core/collision_detection_bullet/test/test_bullet_continuous_collision_checking.cpp index 16c62799ff..0bcc15c7df 100644 --- a/moveit_core/collision_detection_bullet/test/test_bullet_continuous_collision_checking.cpp +++ b/moveit_core/collision_detection_bullet/test/test_bullet_continuous_collision_checking.cpp @@ -37,16 +37,16 @@ #include #include -#include -#include -#include +#include +#include +#include -#include -#include -#include +#include +#include +#include -#include -#include +#include +#include #include #include diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h index 84e7f6266d..6869a8ac77 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h @@ -36,10 +36,10 @@ #pragma once -#include -#include -#include -#include +#include +#include +#include +#include #include #if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0)) diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h index 77a84274cc..855ab66b46 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h @@ -36,10 +36,10 @@ #pragma once -#include -#include +#include +#include -#include +#include namespace collision_detection { diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h index 0a967b90fc..6bc2a772ec 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include namespace collision_detection { diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h index cf5249fd70..98146a6555 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include #if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0)) #include diff --git a/moveit_core/collision_detection_fcl/src/collision_common.cpp b/moveit_core/collision_detection_fcl/src/collision_common.cpp index faf5e8eab4..89ee984e09 100644 --- a/moveit_core/collision_detection_fcl/src/collision_common.cpp +++ b/moveit_core/collision_detection_fcl/src/collision_common.cpp @@ -34,9 +34,9 @@ /* Author: Ioan Sucan, Jia Pan */ -#include +#include #include -#include +#include #include #include #include diff --git a/moveit_core/collision_detection_fcl/src/collision_detector_fcl_plugin_loader.cpp b/moveit_core/collision_detection_fcl/src/collision_detector_fcl_plugin_loader.cpp index dd55132fd2..5ca379d82f 100644 --- a/moveit_core/collision_detection_fcl/src/collision_detector_fcl_plugin_loader.cpp +++ b/moveit_core/collision_detection_fcl/src/collision_detector_fcl_plugin_loader.cpp @@ -34,7 +34,7 @@ /* Author: Bryce Willey */ -#include +#include #include namespace collision_detection diff --git a/moveit_core/collision_detection_fcl/src/collision_env_fcl.cpp b/moveit_core/collision_detection_fcl/src/collision_env_fcl.cpp index 86a48b8320..b57e0767ea 100644 --- a/moveit_core/collision_detection_fcl/src/collision_env_fcl.cpp +++ b/moveit_core/collision_detection_fcl/src/collision_env_fcl.cpp @@ -34,11 +34,11 @@ /* Author: Ioan Sucan, Jens Petit */ -#include -#include -#include +#include +#include +#include -#include +#include #include #include #include diff --git a/moveit_core/collision_detection_fcl/test/test_fcl_collision_detection_panda.cpp b/moveit_core/collision_detection_fcl/test/test_fcl_collision_detection_panda.cpp index 78aa8732b8..63a1dfa437 100644 --- a/moveit_core/collision_detection_fcl/test/test_fcl_collision_detection_panda.cpp +++ b/moveit_core/collision_detection_fcl/test/test_fcl_collision_detection_panda.cpp @@ -34,8 +34,8 @@ /* Author: Jens Petit */ -#include -#include +#include +#include INSTANTIATE_TYPED_TEST_SUITE_P(FCLCollisionCheckPanda, CollisionDetectorPandaTest, collision_detection::CollisionDetectorAllocatorFCL); diff --git a/moveit_core/collision_detection_fcl/test/test_fcl_collision_detection_pr2.cpp b/moveit_core/collision_detection_fcl/test/test_fcl_collision_detection_pr2.cpp index 6818fb13a9..e34e28c3f0 100644 --- a/moveit_core/collision_detection_fcl/test/test_fcl_collision_detection_pr2.cpp +++ b/moveit_core/collision_detection_fcl/test/test_fcl_collision_detection_pr2.cpp @@ -34,8 +34,8 @@ /* Author: Jens Petit */ -#include -#include +#include +#include INSTANTIATE_TYPED_TEST_SUITE_P(FCLCollisionCheck, CollisionDetectorTest, collision_detection::CollisionDetectorAllocatorFCL); diff --git a/moveit_core/collision_detection_fcl/test/test_fcl_env.cpp b/moveit_core/collision_detection_fcl/test/test_fcl_env.cpp index e1a59bbddb..53ad6f9d8a 100644 --- a/moveit_core/collision_detection_fcl/test/test_fcl_env.cpp +++ b/moveit_core/collision_detection_fcl/test/test_fcl_env.cpp @@ -36,15 +36,15 @@ #include -#include +#include -#include -#include -#include +#include +#include +#include #include -#include -#include +#include +#include #include #include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h index e40eefdf36..0faa884f90 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h @@ -36,11 +36,11 @@ #pragma once -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include namespace collision_detection { diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h index 188be97465..26c6d5ff73 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include namespace collision_detection { diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h index db557e9cf3..03a3c70a2a 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h @@ -36,10 +36,10 @@ #pragma once -#include -#include +#include +#include -#include +#include namespace collision_detection { diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h index 5887a9cdab..f4e43fb40b 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h @@ -46,9 +46,9 @@ #include #include -#include -#include -#include +#include +#include +#include #include #include #include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h index f971f5a442..7a9c53224c 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h @@ -36,11 +36,11 @@ #pragma once -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include #include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h index 6e8dd80fd3..ef799520a5 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h @@ -36,10 +36,10 @@ #pragma once -#include -#include -#include -#include +#include +#include +#include +#include namespace collision_detection { diff --git a/moveit_core/collision_distance_field/src/collision_common_distance_field.cpp b/moveit_core/collision_distance_field/src/collision_common_distance_field.cpp index 4402a4e44c..dae65836ac 100644 --- a/moveit_core/collision_distance_field/src/collision_common_distance_field.cpp +++ b/moveit_core/collision_distance_field/src/collision_common_distance_field.cpp @@ -34,7 +34,7 @@ /* Author: E. Gil Jones */ -#include +#include #include #include #include diff --git a/moveit_core/collision_distance_field/src/collision_distance_field_types.cpp b/moveit_core/collision_distance_field/src/collision_distance_field_types.cpp index 1754a74b4d..7b0df3a7ce 100644 --- a/moveit_core/collision_distance_field/src/collision_distance_field_types.cpp +++ b/moveit_core/collision_distance_field/src/collision_distance_field_types.cpp @@ -34,10 +34,10 @@ /* Author: E. Gil Jones */ -#include +#include #include -#include -#include +#include +#include #include #include #include diff --git a/moveit_core/collision_distance_field/src/collision_env_distance_field.cpp b/moveit_core/collision_distance_field/src/collision_env_distance_field.cpp index 947ce31263..49e6517a79 100644 --- a/moveit_core/collision_distance_field/src/collision_env_distance_field.cpp +++ b/moveit_core/collision_distance_field/src/collision_env_distance_field.cpp @@ -34,17 +34,17 @@ /* Author: E. Gil Jones */ -#include +#include #include #include #include #include #include #include -#include -#include -#include -#include +#include +#include +#include +#include #include #include #include diff --git a/moveit_core/collision_distance_field/src/collision_env_hybrid.cpp b/moveit_core/collision_distance_field/src/collision_env_hybrid.cpp index 7f1686022b..b0afbd55fd 100644 --- a/moveit_core/collision_distance_field/src/collision_env_hybrid.cpp +++ b/moveit_core/collision_distance_field/src/collision_env_hybrid.cpp @@ -34,8 +34,8 @@ /* Author: E. Gil Jones, Jens Petit */ -#include -#include +#include +#include namespace collision_detection { diff --git a/moveit_core/collision_distance_field/test/test_collision_distance_field.cpp b/moveit_core/collision_distance_field/test/test_collision_distance_field.cpp index de7af9f693..f2c69e9c01 100644 --- a/moveit_core/collision_distance_field/test/test_collision_distance_field.cpp +++ b/moveit_core/collision_distance_field/test/test_collision_distance_field.cpp @@ -34,12 +34,12 @@ /** \author E. Gil Jones */ -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include #include #include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h index 0552766463..32f58b1f3e 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include #include #include /** diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h index a861facf54..0be8a86075 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include #include namespace constraint_samplers diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h index afd036ddcf..428a681430 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include #include #include #include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h index 77577b1a93..33c2808d41 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h @@ -36,7 +36,7 @@ #pragma once -#include +#include #include #include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h index d1f307a040..1f1df0f556 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include #include #include #include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h index 319f2f9322..0a0e1eea60 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h @@ -36,7 +36,7 @@ #pragma once -#include +#include #include namespace constraint_samplers diff --git a/moveit_core/constraint_samplers/src/constraint_sampler.cpp b/moveit_core/constraint_samplers/src/constraint_sampler.cpp index 0f855b14d4..ddc102251d 100644 --- a/moveit_core/constraint_samplers/src/constraint_sampler.cpp +++ b/moveit_core/constraint_samplers/src/constraint_sampler.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include +#include #include #include #include diff --git a/moveit_core/constraint_samplers/src/constraint_sampler_manager.cpp b/moveit_core/constraint_samplers/src/constraint_sampler_manager.cpp index a3fea06024..9353d3015f 100644 --- a/moveit_core/constraint_samplers/src/constraint_sampler_manager.cpp +++ b/moveit_core/constraint_samplers/src/constraint_sampler_manager.cpp @@ -34,9 +34,9 @@ /* Author: Ioan Sucan */ -#include -#include -#include +#include +#include +#include #include #include #include diff --git a/moveit_core/constraint_samplers/src/constraint_sampler_tools.cpp b/moveit_core/constraint_samplers/src/constraint_sampler_tools.cpp index 2aaec85145..f74141f4f3 100644 --- a/moveit_core/constraint_samplers/src/constraint_sampler_tools.cpp +++ b/moveit_core/constraint_samplers/src/constraint_sampler_tools.cpp @@ -34,8 +34,8 @@ /* Author: Ioan Sucan */ -#include -#include +#include +#include #include #include #include diff --git a/moveit_core/constraint_samplers/src/default_constraint_samplers.cpp b/moveit_core/constraint_samplers/src/default_constraint_samplers.cpp index a1869ccc3d..754e350768 100644 --- a/moveit_core/constraint_samplers/src/default_constraint_samplers.cpp +++ b/moveit_core/constraint_samplers/src/default_constraint_samplers.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include +#include #include #include #include diff --git a/moveit_core/constraint_samplers/src/union_constraint_sampler.cpp b/moveit_core/constraint_samplers/src/union_constraint_sampler.cpp index 13983d2ff5..320656ec4a 100644 --- a/moveit_core/constraint_samplers/src/union_constraint_sampler.cpp +++ b/moveit_core/constraint_samplers/src/union_constraint_sampler.cpp @@ -34,8 +34,8 @@ /* Author: Ioan Sucan */ -#include -#include +#include +#include #include #include #include diff --git a/moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.cpp b/moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.cpp index 715c930786..0bf50e5559 100644 --- a/moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.cpp +++ b/moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.cpp @@ -40,7 +40,7 @@ #include #include -#include +#include #include #include "pr2_arm_kinematics_plugin.hpp" diff --git a/moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.h b/moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.h index c362403b7a..ce483038b0 100644 --- a/moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.h +++ b/moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.h @@ -42,7 +42,7 @@ #include #include -#include +#include #include #include #include @@ -56,7 +56,7 @@ #include #endif -#include +#include #include diff --git a/moveit_core/constraint_samplers/test/test_constraint_samplers.cpp b/moveit_core/constraint_samplers/test/test_constraint_samplers.cpp index 2e6074c53c..b977f7add6 100644 --- a/moveit_core/constraint_samplers/test/test_constraint_samplers.cpp +++ b/moveit_core/constraint_samplers/test/test_constraint_samplers.cpp @@ -34,16 +34,16 @@ /* Author: Ioan Sucan */ -#include -#include -#include -#include -#include -#include -#include -#include - -#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include #include #include diff --git a/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h b/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h index e74003a447..5dbda12f17 100644 --- a/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h +++ b/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h @@ -39,7 +39,7 @@ #include #include #include -#include +#include #include /// Namespace for the base class of a MoveIt controller manager diff --git a/moveit_core/distance_field/include/moveit/distance_field/distance_field.h b/moveit_core/distance_field/include/moveit/distance_field/distance_field.h index cfbe2113d4..535918c92d 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/distance_field.h +++ b/moveit_core/distance_field/include/moveit/distance_field/distance_field.h @@ -36,14 +36,14 @@ #pragma once -#include -#include +#include +#include #include #include #include #include #include -#include +#include #include namespace shapes diff --git a/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h b/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h index c9c1a6d78d..96cb39eb51 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h +++ b/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include #include #include #include diff --git a/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h b/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h index c441333d18..b58f2804c1 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h +++ b/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h @@ -39,7 +39,7 @@ #include #include #include -#include +#include namespace distance_field { diff --git a/moveit_core/distance_field/src/distance_field.cpp b/moveit_core/distance_field/src/distance_field.cpp index c619f95d51..6e4d44bebd 100644 --- a/moveit_core/distance_field/src/distance_field.cpp +++ b/moveit_core/distance_field/src/distance_field.cpp @@ -34,8 +34,8 @@ /* Author: Mrinal Kalakrishnan, Ken Anderson, E. Gil Jones */ -#include -#include +#include +#include #include #include #include diff --git a/moveit_core/distance_field/src/find_internal_points.cpp b/moveit_core/distance_field/src/find_internal_points.cpp index 1a4da45820..b3ba81241a 100644 --- a/moveit_core/distance_field/src/find_internal_points.cpp +++ b/moveit_core/distance_field/src/find_internal_points.cpp @@ -34,7 +34,7 @@ /* Author: Acorn Pooley */ -#include +#include void distance_field::findInternalPointsConvex(const bodies::Body& body, double resolution, EigenSTL::vector_Vector3d& points) diff --git a/moveit_core/distance_field/src/propagation_distance_field.cpp b/moveit_core/distance_field/src/propagation_distance_field.cpp index 6b70134120..b088922a31 100644 --- a/moveit_core/distance_field/src/propagation_distance_field.cpp +++ b/moveit_core/distance_field/src/propagation_distance_field.cpp @@ -34,7 +34,7 @@ /* Author: Mrinal Kalakrishnan, Ken Anderson */ -#include +#include #include #include #include diff --git a/moveit_core/distance_field/test/test_distance_field.cpp b/moveit_core/distance_field/test/test_distance_field.cpp index 62cbfe6d63..37e392bbf1 100644 --- a/moveit_core/distance_field/test/test_distance_field.cpp +++ b/moveit_core/distance_field/test/test_distance_field.cpp @@ -36,9 +36,9 @@ #include -#include -#include -#include +#include +#include +#include #include #include #include diff --git a/moveit_core/distance_field/test/test_voxel_grid.cpp b/moveit_core/distance_field/test/test_voxel_grid.cpp index cdd24250e9..9930c94b6c 100644 --- a/moveit_core/distance_field/test/test_voxel_grid.cpp +++ b/moveit_core/distance_field/test/test_voxel_grid.cpp @@ -36,7 +36,7 @@ #include -#include +#include #include using namespace distance_field; diff --git a/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h b/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h index 048c937428..c3df5dae43 100644 --- a/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h +++ b/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h @@ -40,7 +40,7 @@ #include #include -#include +#include #include #include #include diff --git a/moveit_core/dynamics_solver/src/dynamics_solver.cpp b/moveit_core/dynamics_solver/src/dynamics_solver.cpp index 9c39863869..edf4e27fcb 100644 --- a/moveit_core/dynamics_solver/src/dynamics_solver.cpp +++ b/moveit_core/dynamics_solver/src/dynamics_solver.cpp @@ -34,7 +34,7 @@ /* Author: Sachin Chitta */ -#include +#include // KDL #include #include diff --git a/moveit_core/exceptions/src/exceptions.cpp b/moveit_core/exceptions/src/exceptions.cpp index 05cc9bc7ae..2a58c6ab18 100644 --- a/moveit_core/exceptions/src/exceptions.cpp +++ b/moveit_core/exceptions/src/exceptions.cpp @@ -34,7 +34,7 @@ /* Author: Acorn Pooley, Ioan Sucan */ -#include +#include #include #include #include diff --git a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h index 5684d55fcf..c462e6e95e 100644 --- a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h +++ b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h @@ -36,11 +36,11 @@ #pragma once -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include #include diff --git a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h index 956b45054d..72a9632006 100644 --- a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h +++ b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h @@ -40,7 +40,7 @@ #include #include #include -#include +#include #include namespace XmlRpc diff --git a/moveit_core/kinematic_constraints/src/kinematic_constraint.cpp b/moveit_core/kinematic_constraints/src/kinematic_constraint.cpp index a56678402e..022d7a7196 100644 --- a/moveit_core/kinematic_constraints/src/kinematic_constraint.cpp +++ b/moveit_core/kinematic_constraints/src/kinematic_constraint.cpp @@ -34,11 +34,11 @@ /* Author: Ioan Sucan */ -#include +#include #include #include -#include -#include +#include +#include #include #include #include diff --git a/moveit_core/kinematic_constraints/src/utils.cpp b/moveit_core/kinematic_constraints/src/utils.cpp index 96fa5a70bc..17bf578f86 100644 --- a/moveit_core/kinematic_constraints/src/utils.cpp +++ b/moveit_core/kinematic_constraints/src/utils.cpp @@ -37,8 +37,8 @@ #include #include -#include -#include +#include +#include #include #include #include diff --git a/moveit_core/kinematic_constraints/test/test_constraints.cpp b/moveit_core/kinematic_constraints/test/test_constraints.cpp index 3faa4db05c..9dedc66303 100644 --- a/moveit_core/kinematic_constraints/test/test_constraints.cpp +++ b/moveit_core/kinematic_constraints/test/test_constraints.cpp @@ -34,13 +34,13 @@ /* Author: Ioan Sucan, E. Gil Jones */ -#include +#include #include #include #include #include #include -#include +#include class LoadPlanningModelsPr2 : public testing::Test { diff --git a/moveit_core/kinematic_constraints/test/test_orientation_constraints.cpp b/moveit_core/kinematic_constraints/test/test_orientation_constraints.cpp index 1a26e34abe..235f4f3075 100644 --- a/moveit_core/kinematic_constraints/test/test_orientation_constraints.cpp +++ b/moveit_core/kinematic_constraints/test/test_orientation_constraints.cpp @@ -34,7 +34,7 @@ /* Author: Jeroen De Maeyer */ -#include +#include #include #include @@ -42,7 +42,7 @@ #include #include -#include +#include class SphericalRobot : public testing::Test { diff --git a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h index 1963d7c389..7c8e97f7bb 100644 --- a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h +++ b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h @@ -38,14 +38,14 @@ #include #include -#include +#include #include #include #include #include #include -#include +#include namespace moveit { diff --git a/moveit_core/kinematics_base/src/kinematics_base.cpp b/moveit_core/kinematics_base/src/kinematics_base.cpp index 3b8d61854d..a97c7f96d2 100644 --- a/moveit_core/kinematics_base/src/kinematics_base.cpp +++ b/moveit_core/kinematics_base/src/kinematics_base.cpp @@ -34,8 +34,8 @@ /* Author: Sachin Chitta, Dave Coleman */ -#include -#include +#include +#include #include #include diff --git a/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h b/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h index daabe12ccb..4e27a4dfd4 100644 --- a/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h +++ b/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h @@ -36,7 +36,7 @@ #pragma once -#include +#include /** @brief Namespace for kinematics metrics */ namespace kinematics_metrics diff --git a/moveit_core/kinematics_metrics/src/kinematics_metrics.cpp b/moveit_core/kinematics_metrics/src/kinematics_metrics.cpp index c6ab4eaf44..10023dedb2 100644 --- a/moveit_core/kinematics_metrics/src/kinematics_metrics.cpp +++ b/moveit_core/kinematics_metrics/src/kinematics_metrics.cpp @@ -38,7 +38,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/moveit_core/macros/include/moveit/macros/class_forward.h b/moveit_core/macros/include/moveit/macros/class_forward.h index c4f1cbf6d6..44db6cd231 100644 --- a/moveit_core/macros/include/moveit/macros/class_forward.h +++ b/moveit_core/macros/include/moveit/macros/class_forward.h @@ -36,7 +36,7 @@ #pragma once -#include +#include /** * \def MOVEIT_CLASS_FORWARD diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h index 361b14852e..def9fa48ec 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h @@ -74,9 +74,9 @@ c --------x--- v | #include -#include -#include -#include +#include +#include +#include #include #include diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h index 8f5e5b362f..aa7d4af124 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h @@ -42,8 +42,8 @@ #include #include -#include -#include +#include +#include namespace online_signal_smoothing { diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h index 13cf36a742..db523cfa2e 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h @@ -40,8 +40,8 @@ Description: Applies jerk/acceleration/velocity limits to online motion commands #include -#include -#include +#include +#include #include #include diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h index e2dc886aaf..4a46dbe063 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h @@ -40,8 +40,8 @@ #include -#include -#include +#include +#include #include diff --git a/moveit_core/online_signal_smoothing/src/acceleration_filter.cpp b/moveit_core/online_signal_smoothing/src/acceleration_filter.cpp index 5e47aaec69..3e6b3de049 100644 --- a/moveit_core/online_signal_smoothing/src/acceleration_filter.cpp +++ b/moveit_core/online_signal_smoothing/src/acceleration_filter.cpp @@ -32,7 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include #include // Disable -Wold-style-cast because all _THROTTLE macros trigger this diff --git a/moveit_core/online_signal_smoothing/src/butterworth_filter.cpp b/moveit_core/online_signal_smoothing/src/butterworth_filter.cpp index d0d533799b..4792e93f4e 100644 --- a/moveit_core/online_signal_smoothing/src/butterworth_filter.cpp +++ b/moveit_core/online_signal_smoothing/src/butterworth_filter.cpp @@ -36,7 +36,7 @@ Description: A first-order Butterworth low-pass filter. There is only one parameter to tune. */ -#include +#include #include #include diff --git a/moveit_core/online_signal_smoothing/src/ruckig_filter.cpp b/moveit_core/online_signal_smoothing/src/ruckig_filter.cpp index b689620761..14845e8d51 100644 --- a/moveit_core/online_signal_smoothing/src/ruckig_filter.cpp +++ b/moveit_core/online_signal_smoothing/src/ruckig_filter.cpp @@ -32,7 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include #include #include diff --git a/moveit_core/online_signal_smoothing/src/smoothing_base_class.cpp b/moveit_core/online_signal_smoothing/src/smoothing_base_class.cpp index f39984f3d4..f88f3a220d 100644 --- a/moveit_core/online_signal_smoothing/src/smoothing_base_class.cpp +++ b/moveit_core/online_signal_smoothing/src/smoothing_base_class.cpp @@ -36,7 +36,7 @@ Description: Base class implementation for online smoothing plugins */ -#include +#include namespace online_signal_smoothing { diff --git a/moveit_core/online_signal_smoothing/test/test_acceleration_filter.cpp b/moveit_core/online_signal_smoothing/test/test_acceleration_filter.cpp index aeff731f2a..410c3b5c06 100644 --- a/moveit_core/online_signal_smoothing/test/test_acceleration_filter.cpp +++ b/moveit_core/online_signal_smoothing/test/test_acceleration_filter.cpp @@ -33,8 +33,8 @@ *********************************************************************/ #include -#include -#include +#include +#include constexpr std::string_view PLANNING_GROUP_NAME = "panda_arm"; constexpr size_t PANDA_NUM_JOINTS = 7u; diff --git a/moveit_core/online_signal_smoothing/test/test_butterworth_filter.cpp b/moveit_core/online_signal_smoothing/test/test_butterworth_filter.cpp index f2f944082a..02b047cf94 100644 --- a/moveit_core/online_signal_smoothing/test/test_butterworth_filter.cpp +++ b/moveit_core/online_signal_smoothing/test/test_butterworth_filter.cpp @@ -40,7 +40,7 @@ */ #include -#include +#include TEST(SMOOTHING_PLUGINS, FilterConverge) { diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h index 76bb51bb3e..2aaa2e8a05 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h @@ -36,10 +36,10 @@ #pragma once -#include -#include -#include -#include +#include +#include +#include +#include #include #include #include diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h index f001f6792d..981c24a273 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h @@ -38,9 +38,9 @@ #pragma once -#include -#include -#include +#include +#include +#include #include #include diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h index 7f8bbadcb6..1fdf7c7c20 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include #include #include #include diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h index ddade4c5d4..0e376d5699 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include #include #include diff --git a/moveit_core/planning_interface/src/planning_interface.cpp b/moveit_core/planning_interface/src/planning_interface.cpp index 67ec7fe7d5..5aa72cbe25 100644 --- a/moveit_core/planning_interface/src/planning_interface.cpp +++ b/moveit_core/planning_interface/src/planning_interface.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include +#include #include #include #include diff --git a/moveit_core/planning_interface/src/planning_response.cpp b/moveit_core/planning_interface/src/planning_response.cpp index 8b93391e80..6b114e2ae2 100644 --- a/moveit_core/planning_interface/src/planning_response.cpp +++ b/moveit_core/planning_interface/src/planning_response.cpp @@ -34,8 +34,8 @@ /* Author: Ioan Sucan */ -#include -#include +#include +#include void planning_interface::MotionPlanResponse::getMessage(moveit_msgs::msg::MotionPlanResponse& msg) const { diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h index 3d71a117e7..5522293624 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h @@ -36,16 +36,16 @@ #pragma once -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include #include #include #include @@ -59,7 +59,7 @@ #include #include -#include +#include /** \brief This namespace includes the central class for representing planning contexts */ namespace planning_scene diff --git a/moveit_core/planning_scene/src/planning_scene.cpp b/moveit_core/planning_scene/src/planning_scene.cpp index 8655117fb8..b284f3ad3f 100644 --- a/moveit_core/planning_scene/src/planning_scene.cpp +++ b/moveit_core/planning_scene/src/planning_scene.cpp @@ -35,16 +35,16 @@ /* Author: Ioan Sucan */ #include -#include -#include -#include +#include +#include +#include #include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include #include #include #include diff --git a/moveit_core/planning_scene/test/test_collision_objects.cpp b/moveit_core/planning_scene/test/test_collision_objects.cpp index 945f6e39a4..69d45f3927 100644 --- a/moveit_core/planning_scene/test/test_collision_objects.cpp +++ b/moveit_core/planning_scene/test/test_collision_objects.cpp @@ -35,9 +35,9 @@ /* Author: Michael 'v4hn' Goerner */ #include -#include -#include -#include +#include +#include +#include #include #include #include diff --git a/moveit_core/planning_scene/test/test_multi_threaded.cpp b/moveit_core/planning_scene/test/test_multi_threaded.cpp index 4d281f8b5d..a8dc71d824 100644 --- a/moveit_core/planning_scene/test/test_multi_threaded.cpp +++ b/moveit_core/planning_scene/test/test_multi_threaded.cpp @@ -34,15 +34,15 @@ /* Author: Jens Petit */ -#include -#include -#include -#include +#include +#include +#include +#include #include #include -#include -#include +#include +#include const int TRIALS = 1000; const int THREADS = 2; diff --git a/moveit_core/planning_scene/test/test_planning_scene.cpp b/moveit_core/planning_scene/test/test_planning_scene.cpp index 909f3f6576..ae697ee8a8 100644 --- a/moveit_core/planning_scene/test/test_planning_scene.cpp +++ b/moveit_core/planning_scene/test/test_planning_scene.cpp @@ -35,10 +35,10 @@ /* Author: Ioan Sucan */ #include -#include -#include -#include -#include +#include +#include +#include +#include #include #include #include @@ -47,8 +47,8 @@ #include #include -#include -#include +#include +#include // Test not setting the object's pose should use the shape pose as the object pose TEST(PlanningScene, TestOneShapeObjectPose) diff --git a/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h index 9f3356fdcb..c7ab04c544 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h @@ -36,7 +36,7 @@ #pragma once -#include +#include namespace moveit { diff --git a/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h index 484779512d..859bcd2c7a 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h @@ -36,7 +36,7 @@ #pragma once -#include +#include namespace moveit { diff --git a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h index c63112fde4..54299304c1 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h +++ b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h @@ -37,9 +37,9 @@ #pragma once -#include -#include -#include +#include +#include +#include #include #include #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/link_model.h b/moveit_core/robot_model/include/moveit/robot_model/link_model.h index a9cd17df07..323e4dca67 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/link_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/link_model.h @@ -42,7 +42,7 @@ #include #include #include -#include +#include #include namespace shapes diff --git a/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h index cc95677872..88cf4eb010 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h @@ -36,7 +36,7 @@ #pragma once -#include +#include namespace moveit { diff --git a/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h index c69e523a55..85ac165ef5 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h @@ -36,7 +36,7 @@ #pragma once -#include +#include namespace moveit { diff --git a/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h index 935a12a697..90798d407a 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h @@ -36,7 +36,7 @@ #pragma once -#include +#include namespace moveit { diff --git a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h index 6c4d1aad1b..2cc06f984d 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h @@ -37,17 +37,17 @@ #pragma once -#include -#include +#include +#include #include // joint types -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include #include #include #include diff --git a/moveit_core/robot_model/src/aabb.cpp b/moveit_core/robot_model/src/aabb.cpp index 91552b0fa2..04e1372f15 100644 --- a/moveit_core/robot_model/src/aabb.cpp +++ b/moveit_core/robot_model/src/aabb.cpp @@ -34,7 +34,7 @@ /* Author: Martin Pecka */ -#include +#include #include void moveit::core::AABB::extendWithTransformedBox(const Eigen::Isometry3d& transform, const Eigen::Vector3d& box) diff --git a/moveit_core/robot_model/src/fixed_joint_model.cpp b/moveit_core/robot_model/src/fixed_joint_model.cpp index 5873f0c951..9a230e0dab 100644 --- a/moveit_core/robot_model/src/fixed_joint_model.cpp +++ b/moveit_core/robot_model/src/fixed_joint_model.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include +#include namespace moveit { diff --git a/moveit_core/robot_model/src/floating_joint_model.cpp b/moveit_core/robot_model/src/floating_joint_model.cpp index 776ed5efd9..e3b6e3255b 100644 --- a/moveit_core/robot_model/src/floating_joint_model.cpp +++ b/moveit_core/robot_model/src/floating_joint_model.cpp @@ -39,7 +39,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/moveit_core/robot_model/src/joint_model.cpp b/moveit_core/robot_model/src/joint_model.cpp index 933c65e5ab..5da2403476 100644 --- a/moveit_core/robot_model/src/joint_model.cpp +++ b/moveit_core/robot_model/src/joint_model.cpp @@ -35,9 +35,9 @@ /* Author: Ioan Sucan */ -#include -#include -#include +#include +#include +#include #include namespace moveit diff --git a/moveit_core/robot_model/src/joint_model_group.cpp b/moveit_core/robot_model/src/joint_model_group.cpp index 2776bb0c9d..a9d23c33ea 100644 --- a/moveit_core/robot_model/src/joint_model_group.cpp +++ b/moveit_core/robot_model/src/joint_model_group.cpp @@ -35,10 +35,10 @@ /* Author: Ioan Sucan, Dave Coleman */ -#include -#include -#include -#include +#include +#include +#include +#include #include #include #include diff --git a/moveit_core/robot_model/src/link_model.cpp b/moveit_core/robot_model/src/link_model.cpp index da3e447c14..98150b935f 100644 --- a/moveit_core/robot_model/src/link_model.cpp +++ b/moveit_core/robot_model/src/link_model.cpp @@ -34,11 +34,11 @@ /* Author: Ioan Sucan */ -#include -#include +#include +#include #include #include -#include +#include namespace moveit { diff --git a/moveit_core/robot_model/src/planar_joint_model.cpp b/moveit_core/robot_model/src/planar_joint_model.cpp index 6bede60c14..deb7b04951 100644 --- a/moveit_core/robot_model/src/planar_joint_model.cpp +++ b/moveit_core/robot_model/src/planar_joint_model.cpp @@ -39,7 +39,7 @@ #include #include #include -#include +#include namespace moveit { diff --git a/moveit_core/robot_model/src/prismatic_joint_model.cpp b/moveit_core/robot_model/src/prismatic_joint_model.cpp index 81e9128053..7a486288d0 100644 --- a/moveit_core/robot_model/src/prismatic_joint_model.cpp +++ b/moveit_core/robot_model/src/prismatic_joint_model.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include +#include #include namespace moveit diff --git a/moveit_core/robot_model/src/revolute_joint_model.cpp b/moveit_core/robot_model/src/revolute_joint_model.cpp index 524632159c..515cc3ea3a 100644 --- a/moveit_core/robot_model/src/revolute_joint_model.cpp +++ b/moveit_core/robot_model/src/revolute_joint_model.cpp @@ -35,7 +35,7 @@ /* Author: Ioan Sucan */ -#include +#include #include #include #include diff --git a/moveit_core/robot_model/src/robot_model.cpp b/moveit_core/robot_model/src/robot_model.cpp index f65ff86a11..c6634f5b5d 100644 --- a/moveit_core/robot_model/src/robot_model.cpp +++ b/moveit_core/robot_model/src/robot_model.cpp @@ -35,7 +35,7 @@ /* Author: Ioan Sucan */ -#include +#include #include #include #include diff --git a/moveit_core/robot_model/test/test.cpp b/moveit_core/robot_model/test/test.cpp index db76212b2e..5ed7236fd4 100644 --- a/moveit_core/robot_model/test/test.cpp +++ b/moveit_core/robot_model/test/test.cpp @@ -34,12 +34,12 @@ /* Author: Ioan Sucan */ -#include +#include #include #include #include -#include +#include class LoadPlanningModelsPr2 : public testing::Test { diff --git a/moveit_core/robot_state/include/moveit/robot_state/attached_body.h b/moveit_core/robot_state/include/moveit/robot_state/attached_body.h index a7c74d0905..4ef09a2518 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/attached_body.h +++ b/moveit_core/robot_state/include/moveit/robot_state/attached_body.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include #include #include #include diff --git a/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h b/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h index 089eba6b8f..f7843c8996 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h +++ b/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h @@ -38,7 +38,7 @@ #pragma once -#include +#include namespace moveit { diff --git a/moveit_core/robot_state/include/moveit/robot_state/conversions.h b/moveit_core/robot_state/include/moveit/robot_state/conversions.h index 833ad3e464..4f369659a4 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/conversions.h +++ b/moveit_core/robot_state/include/moveit/robot_state/conversions.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include #include namespace moveit diff --git a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h index cdac228288..7f2e3637f8 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h +++ b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h @@ -37,9 +37,9 @@ #pragma once -#include -#include -#include +#include +#include +#include #include #include #include diff --git a/moveit_core/robot_state/src/attached_body.cpp b/moveit_core/robot_state/src/attached_body.cpp index 3da139aac1..3a606dfe5d 100644 --- a/moveit_core/robot_state/src/attached_body.cpp +++ b/moveit_core/robot_state/src/attached_body.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include +#include #include #include diff --git a/moveit_core/robot_state/src/cartesian_interpolator.cpp b/moveit_core/robot_state/src/cartesian_interpolator.cpp index 71b927daaf..0c85e910e9 100644 --- a/moveit_core/robot_state/src/cartesian_interpolator.cpp +++ b/moveit_core/robot_state/src/cartesian_interpolator.cpp @@ -37,7 +37,7 @@ /* Author: Ioan Sucan, Sachin Chitta, Acorn Pooley, Mario Prats, Dave Coleman, Robert Haschke */ #include -#include +#include #include #include #include diff --git a/moveit_core/robot_state/src/conversions.cpp b/moveit_core/robot_state/src/conversions.cpp index 89538525b5..67082811aa 100644 --- a/moveit_core/robot_state/src/conversions.cpp +++ b/moveit_core/robot_state/src/conversions.cpp @@ -36,7 +36,7 @@ /* Author: Ioan Sucan, Dave Coleman */ #include -#include +#include #include #include #include diff --git a/moveit_core/robot_state/src/robot_state.cpp b/moveit_core/robot_state/src/robot_state.cpp index 1f1593ca78..ff847bcb54 100644 --- a/moveit_core/robot_state/src/robot_state.cpp +++ b/moveit_core/robot_state/src/robot_state.cpp @@ -37,9 +37,9 @@ #include #include -#include -#include -#include +#include +#include +#include #include #include #include @@ -47,8 +47,8 @@ #include #include #include -#include -#include +#include +#include #include namespace moveit diff --git a/moveit_core/robot_state/test/robot_state_benchmark.cpp b/moveit_core/robot_state/test/robot_state_benchmark.cpp index 06c40df745..161e280877 100644 --- a/moveit_core/robot_state/test/robot_state_benchmark.cpp +++ b/moveit_core/robot_state/test/robot_state_benchmark.cpp @@ -41,9 +41,9 @@ #include #include #include -#include -#include -#include +#include +#include +#include // Robot and planning group for benchmarks. constexpr char PANDA_TEST_ROBOT[] = "panda"; diff --git a/moveit_core/robot_state/test/robot_state_test.cpp b/moveit_core/robot_state/test/robot_state_test.cpp index e1d710805c..5af16e3788 100644 --- a/moveit_core/robot_state/test/robot_state_test.cpp +++ b/moveit_core/robot_state/test/robot_state_test.cpp @@ -33,9 +33,9 @@ *********************************************************************/ /* Author: Ioan Sucan */ -#include -#include -#include +#include +#include +#include #include #include #include diff --git a/moveit_core/robot_state/test/test_aabb.cpp b/moveit_core/robot_state/test/test_aabb.cpp index 79936d45dc..cae7b5f730 100644 --- a/moveit_core/robot_state/test/test_aabb.cpp +++ b/moveit_core/robot_state/test/test_aabb.cpp @@ -34,16 +34,16 @@ /* Author: Martin Pecka */ -#include -#include -#include +#include +#include +#include #include #include #include #include #include #include -#include +#include // To visualize bbox of the PR2, set this to 1. #ifndef VISUALIZE_PR2_RVIZ diff --git a/moveit_core/robot_state/test/test_cartesian_interpolator.cpp b/moveit_core/robot_state/test/test_cartesian_interpolator.cpp index c15f172b76..d5af24e429 100644 --- a/moveit_core/robot_state/test/test_cartesian_interpolator.cpp +++ b/moveit_core/robot_state/test/test_cartesian_interpolator.cpp @@ -34,11 +34,11 @@ /* Author: Michael Lautman */ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include diff --git a/moveit_core/robot_state/test/test_kinematic_complex.cpp b/moveit_core/robot_state/test/test_kinematic_complex.cpp index 973c5560a5..b4aa27dba5 100644 --- a/moveit_core/robot_state/test/test_kinematic_complex.cpp +++ b/moveit_core/robot_state/test/test_kinematic_complex.cpp @@ -34,15 +34,15 @@ /* Author: Ioan Sucan */ -#include -#include -#include +#include +#include +#include #include #include #include #include -#include +#include constexpr double EPSILON = 1e-2; constexpr double M_TAU = 2 * M_PI; diff --git a/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h index ed2887e2a2..576a65f318 100644 --- a/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h +++ b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include #include #include #include diff --git a/moveit_core/robot_trajectory/src/robot_trajectory.cpp b/moveit_core/robot_trajectory/src/robot_trajectory.cpp index 8e0eed38be..ee1fe5b351 100644 --- a/moveit_core/robot_trajectory/src/robot_trajectory.cpp +++ b/moveit_core/robot_trajectory/src/robot_trajectory.cpp @@ -35,8 +35,8 @@ /* Author: Ioan Sucan, Adam Leeper */ #include -#include -#include +#include +#include #include #include #include diff --git a/moveit_core/robot_trajectory/test/test_robot_trajectory.cpp b/moveit_core/robot_trajectory/test/test_robot_trajectory.cpp index 8ffdcb1a8a..16793dd43b 100644 --- a/moveit_core/robot_trajectory/test/test_robot_trajectory.cpp +++ b/moveit_core/robot_trajectory/test/test_robot_trajectory.cpp @@ -34,10 +34,10 @@ /* Author: Ioan Sucan */ -#include -#include -#include -#include +#include +#include +#include +#include #include #include diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h index 26038d1bbc..b22ea520cc 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h @@ -37,7 +37,7 @@ #include #include -#include +#include #include namespace trajectory_processing diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h index 8f7b90ec03..cba0df41ef 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h @@ -40,8 +40,8 @@ #include #include -#include -#include +#include +#include namespace trajectory_processing { diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h index ece7e9ea1e..c9854bd43c 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h @@ -1,6 +1,6 @@ #pragma once -#include +#include namespace trajectory_processing { diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h index 876f3af06c..daa1f1f00b 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h @@ -37,8 +37,8 @@ #pragma once #include -#include -#include +#include +#include namespace trajectory_processing { diff --git a/moveit_core/trajectory_processing/src/ruckig_traj_smoothing.cpp b/moveit_core/trajectory_processing/src/ruckig_traj_smoothing.cpp index 84c27c8c22..db1e4c1285 100644 --- a/moveit_core/trajectory_processing/src/ruckig_traj_smoothing.cpp +++ b/moveit_core/trajectory_processing/src/ruckig_traj_smoothing.cpp @@ -39,7 +39,7 @@ #include #include #include -#include +#include #include #include diff --git a/moveit_core/trajectory_processing/src/time_optimal_trajectory_generation.cpp b/moveit_core/trajectory_processing/src/time_optimal_trajectory_generation.cpp index ad9225b34a..091ba1ab42 100644 --- a/moveit_core/trajectory_processing/src/time_optimal_trajectory_generation.cpp +++ b/moveit_core/trajectory_processing/src/time_optimal_trajectory_generation.cpp @@ -42,7 +42,7 @@ #include #include #include -#include +#include #include #include diff --git a/moveit_core/trajectory_processing/src/trajectory_tools.cpp b/moveit_core/trajectory_processing/src/trajectory_tools.cpp index cca3586187..f89dae256f 100644 --- a/moveit_core/trajectory_processing/src/trajectory_tools.cpp +++ b/moveit_core/trajectory_processing/src/trajectory_tools.cpp @@ -34,9 +34,9 @@ /* Author: Ioan Sucan */ -#include -#include -#include +#include +#include +#include #include #include diff --git a/moveit_core/trajectory_processing/test/robot_trajectory_benchmark.cpp b/moveit_core/trajectory_processing/test/robot_trajectory_benchmark.cpp index c0eb07be11..413d37cdef 100644 --- a/moveit_core/trajectory_processing/test/robot_trajectory_benchmark.cpp +++ b/moveit_core/trajectory_processing/test/robot_trajectory_benchmark.cpp @@ -37,11 +37,11 @@ // To run this benchmark, 'cd' to the build/moveit_core/trajectory_processing directory and directly run the binary. #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include // Robot and planning group to use in the benchmarks. constexpr char TEST_ROBOT[] = "panda"; diff --git a/moveit_core/trajectory_processing/test/test_ruckig_traj_smoothing.cpp b/moveit_core/trajectory_processing/test/test_ruckig_traj_smoothing.cpp index e7d2ef6737..6d1ae7c8c0 100644 --- a/moveit_core/trajectory_processing/test/test_ruckig_traj_smoothing.cpp +++ b/moveit_core/trajectory_processing/test/test_ruckig_traj_smoothing.cpp @@ -34,9 +34,9 @@ /* Author: Andy Zelenak */ #include -#include -#include -#include +#include +#include +#include namespace { diff --git a/moveit_core/trajectory_processing/test/test_time_optimal_trajectory_generation.cpp b/moveit_core/trajectory_processing/test/test_time_optimal_trajectory_generation.cpp index ba3f9681cb..9c0ae63ddd 100644 --- a/moveit_core/trajectory_processing/test/test_time_optimal_trajectory_generation.cpp +++ b/moveit_core/trajectory_processing/test/test_time_optimal_trajectory_generation.cpp @@ -37,8 +37,8 @@ */ #include -#include -#include +#include +#include using trajectory_processing::Path; using trajectory_processing::TimeOptimalTrajectoryGeneration; diff --git a/moveit_core/transforms/include/moveit/transforms/transforms.h b/moveit_core/transforms/include/moveit/transforms/transforms.h index 7b31fbb4f4..589c12ea2e 100644 --- a/moveit_core/transforms/include/moveit/transforms/transforms.h +++ b/moveit_core/transforms/include/moveit/transforms/transforms.h @@ -38,7 +38,7 @@ #include #include -#include +#include #include namespace moveit diff --git a/moveit_core/transforms/src/transforms.cpp b/moveit_core/transforms/src/transforms.cpp index 14a57b2c6e..808f18e5d6 100644 --- a/moveit_core/transforms/src/transforms.cpp +++ b/moveit_core/transforms/src/transforms.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include +#include #include #include #include diff --git a/moveit_core/transforms/test/test_transforms.cpp b/moveit_core/transforms/test/test_transforms.cpp index 59725dba3e..e00a1a8816 100644 --- a/moveit_core/transforms/test/test_transforms.cpp +++ b/moveit_core/transforms/test/test_transforms.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include +#include #include #include #include diff --git a/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h b/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h index a419d4cc4e..f8355d92f8 100644 --- a/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h +++ b/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h @@ -43,7 +43,7 @@ #else #include #endif -#include +#include #include #include diff --git a/moveit_core/utils/src/lexical_casts.cpp b/moveit_core/utils/src/lexical_casts.cpp index 2682344bcc..6139a86120 100644 --- a/moveit_core/utils/src/lexical_casts.cpp +++ b/moveit_core/utils/src/lexical_casts.cpp @@ -34,7 +34,7 @@ /* Author: Simon Schmeisser */ -#include +#include #include #include diff --git a/moveit_core/utils/src/message_checks.cpp b/moveit_core/utils/src/message_checks.cpp index 686ae5a7f1..8d4758ce99 100644 --- a/moveit_core/utils/src/message_checks.cpp +++ b/moveit_core/utils/src/message_checks.cpp @@ -34,7 +34,7 @@ /* Author: Michael Goerner */ -#include +#include namespace moveit { diff --git a/moveit_core/utils/src/rclcpp_utils.cpp b/moveit_core/utils/src/rclcpp_utils.cpp index 5979b9e353..df84934bce 100644 --- a/moveit_core/utils/src/rclcpp_utils.cpp +++ b/moveit_core/utils/src/rclcpp_utils.cpp @@ -25,7 +25,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include +#include namespace rclcpp { diff --git a/moveit_core/utils/src/robot_model_test_utils.cpp b/moveit_core/utils/src/robot_model_test_utils.cpp index cc39f6caf8..eea311fbec 100644 --- a/moveit_core/utils/src/robot_model_test_utils.cpp +++ b/moveit_core/utils/src/robot_model_test_utils.cpp @@ -38,7 +38,7 @@ #include #include #include -#include +#include #include #include #include @@ -46,7 +46,7 @@ #include -#include +#include namespace moveit { diff --git a/moveit_core/version/CMakeLists.txt b/moveit_core/version/CMakeLists.txt index 3d70285c09..f41c589a2d 100644 --- a/moveit_core/version/CMakeLists.txt +++ b/moveit_core/version/CMakeLists.txt @@ -23,12 +23,12 @@ add_custom_command( WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}) add_custom_target( - version_h + version_hpp DEPENDS always_rebuild COMMENT "Generating version.hpp") add_executable(moveit_version version.cpp) -add_dependencies(moveit_version version_h) +add_dependencies(moveit_version version_hpp) target_include_directories(moveit_version PRIVATE ${CMAKE_BINARY_DIR}/include/moveit_core) diff --git a/moveit_core/version/version.cmake b/moveit_core/version/version.cmake index 13757b7eb3..3c1b7bc4bc 100644 --- a/moveit_core/version/version.cmake +++ b/moveit_core/version/version.cmake @@ -34,5 +34,5 @@ if(NOT "${MOVEIT_VERSION_EXTRA}" STREQUAL "") string(APPEND MOVEIT_VERSION "-${MOVEIT_VERSION_EXTRA}") endif() -configure_file("version.h.in" +configure_file("version.hpp.in" "${VERSION_FILE_PATH}/moveit_core/moveit/version.hpp") diff --git a/moveit_core/version/version.cpp b/moveit_core/version/version.cpp index 498c61cd4c..bd526c63f6 100644 --- a/moveit_core/version/version.cpp +++ b/moveit_core/version/version.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include +#include #include #include diff --git a/moveit_core/version/version.h.in b/moveit_core/version/version.hpp.in similarity index 100% rename from moveit_core/version/version.h.in rename to moveit_core/version/version.hpp.in diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/README.md b/moveit_kinematics/cached_ik_kinematics_plugin/README.md index d0c82167af..b7fe385543 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/README.md +++ b/moveit_kinematics/cached_ik_kinematics_plugin/README.md @@ -57,7 +57,7 @@ Below is a complete list of all arguments: The Cached IK Kinematics Plugin is implemented as a wrapper around classed derived from the `kinematics::KinematicsBase` [abstract base class](http://docs.ros.org/en/latest/api/moveit_core/html/cpp/classkinematics_1_1KinematicsBase.html). Wrappers for the `kdl_kinematics_plugin::KDLKinematicsPlugin` and `srv_kinematics_plugin::SrvKinematicsPlugin` classes are already included in the plugin. For any other solver, you can create a new kinematics plugin. The C++ code for doing so is extremely simple; here is the code to create a wrapper for the KDL solver: #include "cached_ik_kinematics_plugin.hpp" - #include + #include #include PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin, kinematics::KinematicsBase); diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h index 0768388d33..0ca3ff009e 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h @@ -36,10 +36,10 @@ #pragma once -#include -#include -#include -#include +#include +#include +#include +#include #include #include #include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h index cd3700e92d..1c60e31934 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h @@ -38,7 +38,7 @@ #pragma once -#include +#include #include #include #include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/src/cached_ik_kinematics_plugin.cpp b/moveit_kinematics/cached_ik_kinematics_plugin/src/cached_ik_kinematics_plugin.cpp index e103aa2637..fbe26c3e5c 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/src/cached_ik_kinematics_plugin.cpp +++ b/moveit_kinematics/cached_ik_kinematics_plugin/src/cached_ik_kinematics_plugin.cpp @@ -34,9 +34,9 @@ /* Author: Mark Moll */ -#include -#include -#include +#include +#include +#include #include // register CachedIKKinematicsPlugin as a KinematicsBase implementation diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/src/ik_cache.cpp b/moveit_kinematics/cached_ik_kinematics_plugin/src/ik_cache.cpp index 65d2ad4c0c..e6bf5bdbe7 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/src/ik_cache.cpp +++ b/moveit_kinematics/cached_ik_kinematics_plugin/src/ik_cache.cpp @@ -38,7 +38,7 @@ #include #include -#include +#include #include namespace cached_ik_kinematics_plugin diff --git a/moveit_kinematics/ikfast_kinematics_plugin/templates/ikfast61_moveit_plugin_template.cpp b/moveit_kinematics/ikfast_kinematics_plugin/templates/ikfast61_moveit_plugin_template.cpp index fdba5f1f5b..49f506b420 100644 --- a/moveit_kinematics/ikfast_kinematics_plugin/templates/ikfast61_moveit_plugin_template.cpp +++ b/moveit_kinematics/ikfast_kinematics_plugin/templates/ikfast61_moveit_plugin_template.cpp @@ -42,8 +42,8 @@ */ #include -#include -#include +#include +#include #include #include #include diff --git a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h index 6a0901a497..f6bb09f0e5 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h +++ b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h @@ -54,10 +54,10 @@ #include // MoveIt -#include +#include #include -#include -#include +#include +#include #include diff --git a/moveit_kinematics/kdl_kinematics_plugin/src/kdl_kinematics_plugin.cpp b/moveit_kinematics/kdl_kinematics_plugin/src/kdl_kinematics_plugin.cpp index 54d3f0aa4f..3d7f69bac1 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/src/kdl_kinematics_plugin.cpp +++ b/moveit_kinematics/kdl_kinematics_plugin/src/kdl_kinematics_plugin.cpp @@ -34,7 +34,7 @@ /* Author: Sachin Chitta, David Lu!!, Ugo Cupcic */ -#include +#include #include #include diff --git a/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h b/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h index 2283bb510b..84b2289ad3 100644 --- a/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h +++ b/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h @@ -54,8 +54,8 @@ #include // MoveIt -#include -#include +#include +#include namespace srv_kinematics_plugin { diff --git a/moveit_kinematics/srv_kinematics_plugin/src/srv_kinematics_plugin.cpp b/moveit_kinematics/srv_kinematics_plugin/src/srv_kinematics_plugin.cpp index 9538cf080c..44c86b0691 100644 --- a/moveit_kinematics/srv_kinematics_plugin/src/srv_kinematics_plugin.cpp +++ b/moveit_kinematics/srv_kinematics_plugin/src/srv_kinematics_plugin.cpp @@ -35,9 +35,9 @@ /* Author: Dave Coleman, Masaki Murooka */ #include -#include +#include #include -#include +#include #include #include diff --git a/moveit_kinematics/test/benchmark_ik.cpp b/moveit_kinematics/test/benchmark_ik.cpp index da3a0ca323..a09a149735 100644 --- a/moveit_kinematics/test/benchmark_ik.cpp +++ b/moveit_kinematics/test/benchmark_ik.cpp @@ -37,9 +37,9 @@ #include #include #include -#include -#include -#include +#include +#include +#include #include namespace po = boost::program_options; diff --git a/moveit_kinematics/test/test_kinematics_plugin.cpp b/moveit_kinematics/test/test_kinematics_plugin.cpp index 87f870550c..54a082b329 100644 --- a/moveit_kinematics/test/test_kinematics_plugin.cpp +++ b/moveit_kinematics/test/test_kinematics_plugin.cpp @@ -43,17 +43,17 @@ #include // MoveIt -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include -#include +#include #include -#include +#include -#include +#include #include rclcpp::Logger getLogger() diff --git a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h index 908d315fc8..540aa438df 100644 --- a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h +++ b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h @@ -37,7 +37,7 @@ #pragma once #include -#include +#include #include diff --git a/moveit_planners/chomp/chomp_interface/src/chomp_planning_context.cpp b/moveit_planners/chomp/chomp_interface/src/chomp_planning_context.cpp index 5f93522139..122cc2c763 100644 --- a/moveit_planners/chomp/chomp_interface/src/chomp_planning_context.cpp +++ b/moveit_planners/chomp/chomp_interface/src/chomp_planning_context.cpp @@ -35,7 +35,7 @@ /* Author: Chittaranjan Srinivas Swaminathan */ #include -#include +#include namespace chomp_interface { diff --git a/moveit_planners/chomp/chomp_interface/src/chomp_plugin.cpp b/moveit_planners/chomp/chomp_interface/src/chomp_plugin.cpp index 997bf4a964..64f8e7a6cf 100644 --- a/moveit_planners/chomp/chomp_interface/src/chomp_plugin.cpp +++ b/moveit_planners/chomp/chomp_interface/src/chomp_plugin.cpp @@ -33,10 +33,10 @@ *********************************************************************/ #include -#include -#include -#include -#include +#include +#include +#include +#include #include #include diff --git a/moveit_planners/chomp/chomp_interface/test/chomp_moveit_test_panda.cpp b/moveit_planners/chomp/chomp_interface/test/chomp_moveit_test_panda.cpp index 0d84b43521..7c92e7135d 100644 --- a/moveit_planners/chomp/chomp_interface/test/chomp_moveit_test_panda.cpp +++ b/moveit_planners/chomp/chomp_interface/test/chomp_moveit_test_panda.cpp @@ -37,8 +37,8 @@ #include #include -#include -#include +#include +#include class CHOMPMoveitTest : public ::testing::Test { diff --git a/moveit_planners/chomp/chomp_interface/test/chomp_moveit_test_rrbot.cpp b/moveit_planners/chomp/chomp_interface/test/chomp_moveit_test_rrbot.cpp index 7e69f51c41..30b2e3343c 100644 --- a/moveit_planners/chomp/chomp_interface/test/chomp_moveit_test_rrbot.cpp +++ b/moveit_planners/chomp/chomp_interface/test/chomp_moveit_test_rrbot.cpp @@ -35,8 +35,8 @@ /// \author Bence Magyar #include -#include -#include +#include +#include #include class CHOMPMoveitTest : public ::testing::Test diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h index ceb68ab3a5..c6c8fc1f52 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h @@ -40,9 +40,9 @@ #include #include #include -#include -#include -#include +#include +#include +#include #include #include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h index a6bca7c57e..8559261e16 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h @@ -37,10 +37,10 @@ #pragma once #include -#include -#include -#include -#include +#include +#include +#include +#include namespace chomp { diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h index 45e2b8af0d..904db57d9d 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h @@ -37,7 +37,7 @@ #pragma once #include -#include +#include #include #include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h index 06596fa60c..339d3de62b 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h @@ -36,7 +36,7 @@ #pragma once -#include +#include #include #include diff --git a/moveit_planners/chomp/chomp_motion_planner/src/chomp_optimizer.cpp b/moveit_planners/chomp/chomp_motion_planner/src/chomp_optimizer.cpp index f31f48510d..a83a1e1427 100644 --- a/moveit_planners/chomp/chomp_motion_planner/src/chomp_optimizer.cpp +++ b/moveit_planners/chomp/chomp_motion_planner/src/chomp_optimizer.cpp @@ -36,9 +36,9 @@ #include #include -#include -#include -#include +#include +#include +#include #include #include diff --git a/moveit_planners/chomp/chomp_motion_planner/src/chomp_planner.cpp b/moveit_planners/chomp/chomp_motion_planner/src/chomp_planner.cpp index 9b78d26394..d0c82f05c3 100644 --- a/moveit_planners/chomp/chomp_motion_planner/src/chomp_planner.cpp +++ b/moveit_planners/chomp/chomp_motion_planner/src/chomp_planner.cpp @@ -37,7 +37,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h index 2f533778c2..b45c964601 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h @@ -37,11 +37,11 @@ #pragma once #include -#include -#include +#include +#include -#include -#include +#include +#include namespace ompl_interface { diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h index d0f1d4951d..c23babe0ab 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h @@ -37,7 +37,7 @@ #pragma once #include -#include +#include namespace ompl_interface { diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h index fbd735310a..e656fd04eb 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h @@ -36,9 +36,9 @@ #pragma once -#include -#include -#include +#include +#include +#include #include #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h index 7893627c11..9f783ac0bf 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h @@ -37,10 +37,10 @@ #pragma once #include -#include -#include -#include -#include +#include +#include +#include +#include #include namespace ompl_interface diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h index 93b2cc8bc2..7b240a80de 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h @@ -40,9 +40,9 @@ #include -#include -#include -#include +#include +#include +#include #include namespace ompl_interface diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h index bf2c987f43..2a0c6fa6a2 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h @@ -38,7 +38,7 @@ #include #include -#include +#include typedef Eigen::Ref OMPLProjection; diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h index a3fead6927..4124c92665 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h @@ -47,8 +47,8 @@ #pragma once -#include -#include +#include +#include #include namespace ompl_interface @@ -139,7 +139,7 @@ class ConstrainedPlanningStateValidityChecker : public StateValidityChecker * * Code sample that can be used to check all the assumptions: * - * #include + * #include * #include * * // the code below should be pasted at the top of the isValid method diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h index ab6d38fc66..6e5a5e8b81 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h @@ -36,7 +36,7 @@ #pragma once -#include +#include #include #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h index 8790fdadcf..ee0444ec4a 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h @@ -36,9 +36,9 @@ #pragma once -#include -#include -#include +#include +#include +#include #include #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h index 9ae1ee16fa..8276db84c7 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h @@ -36,10 +36,10 @@ #pragma once -#include -#include -#include -#include +#include +#include +#include +#include #include #include #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h index 2423bef0df..57d1c63df2 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include namespace ompl_interface { diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h index e7a8067266..2a6392bd10 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h @@ -37,7 +37,7 @@ #pragma once -#include +#include namespace ompl_interface { diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h index 91d8867a10..26ec40263b 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h @@ -36,7 +36,7 @@ #pragma once -#include +#include namespace ompl_interface { diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h index d45f8b737a..c8d21154c7 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h @@ -36,7 +36,7 @@ #pragma once -#include +#include namespace ompl_interface { diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h index e334322a98..c203be9dd0 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h @@ -37,10 +37,10 @@ #pragma once #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ompl_interface { diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h index bcef1410ac..763d7c3da3 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include #include namespace ompl_interface diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h index 4ebe272e8d..3bdd08a108 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h @@ -36,7 +36,7 @@ #pragma once -#include +#include #include namespace ompl_interface diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h index 12a6daee9e..d0340f99bc 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h @@ -36,7 +36,7 @@ #pragma once -#include +#include namespace ompl_interface { diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h index f14aad9d5b..b9469f9d91 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h @@ -36,10 +36,10 @@ #pragma once -#include -#include -#include -#include +#include +#include +#include +#include #include diff --git a/moveit_planners/ompl/ompl_interface/scripts/generate_state_database.cpp b/moveit_planners/ompl/ompl_interface/scripts/generate_state_database.cpp index ca1b90114c..fe30f37753 100644 --- a/moveit_planners/ompl/ompl_interface/scripts/generate_state_database.cpp +++ b/moveit_planners/ompl/ompl_interface/scripts/generate_state_database.cpp @@ -35,15 +35,15 @@ /* Authors: Ioan Sucan, Michael Goerner */ -#include -#include -#include +#include +#include +#include -#include -#include +#include +#include -#include -#include +#include +#include #include #include diff --git a/moveit_planners/ompl/ompl_interface/src/detail/constrained_goal_sampler.cpp b/moveit_planners/ompl/ompl_interface/src/detail/constrained_goal_sampler.cpp index 84814ac7c0..34afabd9ae 100644 --- a/moveit_planners/ompl/ompl_interface/src/detail/constrained_goal_sampler.cpp +++ b/moveit_planners/ompl/ompl_interface/src/detail/constrained_goal_sampler.cpp @@ -34,9 +34,9 @@ /* Author: Ioan Sucan */ -#include -#include -#include +#include +#include +#include #include #include diff --git a/moveit_planners/ompl/ompl_interface/src/detail/constrained_sampler.cpp b/moveit_planners/ompl/ompl_interface/src/detail/constrained_sampler.cpp index 38a020c57b..cd06ec5c95 100644 --- a/moveit_planners/ompl/ompl_interface/src/detail/constrained_sampler.cpp +++ b/moveit_planners/ompl/ompl_interface/src/detail/constrained_sampler.cpp @@ -34,8 +34,8 @@ /* Author: Ioan Sucan */ -#include -#include +#include +#include #include diff --git a/moveit_planners/ompl/ompl_interface/src/detail/constraints_library.cpp b/moveit_planners/ompl/ompl_interface/src/detail/constraints_library.cpp index 35a94544a7..d066d9f9b4 100644 --- a/moveit_planners/ompl/ompl_interface/src/detail/constraints_library.cpp +++ b/moveit_planners/ompl/ompl_interface/src/detail/constraints_library.cpp @@ -37,8 +37,8 @@ #include #include #include -#include -#include +#include +#include #include #include diff --git a/moveit_planners/ompl/ompl_interface/src/detail/goal_union.cpp b/moveit_planners/ompl/ompl_interface/src/detail/goal_union.cpp index 3827c73be5..ff831846c5 100644 --- a/moveit_planners/ompl/ompl_interface/src/detail/goal_union.cpp +++ b/moveit_planners/ompl/ompl_interface/src/detail/goal_union.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include +#include #include namespace diff --git a/moveit_planners/ompl/ompl_interface/src/detail/ompl_constraints.cpp b/moveit_planners/ompl/ompl_interface/src/detail/ompl_constraints.cpp index a6bb82bde0..155531c44f 100644 --- a/moveit_planners/ompl/ompl_interface/src/detail/ompl_constraints.cpp +++ b/moveit_planners/ompl/ompl_interface/src/detail/ompl_constraints.cpp @@ -37,7 +37,7 @@ #include #include -#include +#include #include #include diff --git a/moveit_planners/ompl/ompl_interface/src/detail/projection_evaluators.cpp b/moveit_planners/ompl/ompl_interface/src/detail/projection_evaluators.cpp index cb938df902..e664d60ba9 100644 --- a/moveit_planners/ompl/ompl_interface/src/detail/projection_evaluators.cpp +++ b/moveit_planners/ompl/ompl_interface/src/detail/projection_evaluators.cpp @@ -34,9 +34,9 @@ /* Author: Ioan Sucan */ -#include -#include -#include +#include +#include +#include #include diff --git a/moveit_planners/ompl/ompl_interface/src/detail/state_validity_checker.cpp b/moveit_planners/ompl/ompl_interface/src/detail/state_validity_checker.cpp index ae626d0cb5..fbd941308c 100644 --- a/moveit_planners/ompl/ompl_interface/src/detail/state_validity_checker.cpp +++ b/moveit_planners/ompl/ompl_interface/src/detail/state_validity_checker.cpp @@ -34,8 +34,8 @@ /* Author: Ioan Sucan, Jeroen De Maeyer */ -#include -#include +#include +#include #include #include #include diff --git a/moveit_planners/ompl/ompl_interface/src/detail/threadsafe_state_storage.cpp b/moveit_planners/ompl/ompl_interface/src/detail/threadsafe_state_storage.cpp index 7d88e8bdb8..bbe598a618 100644 --- a/moveit_planners/ompl/ompl_interface/src/detail/threadsafe_state_storage.cpp +++ b/moveit_planners/ompl/ompl_interface/src/detail/threadsafe_state_storage.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include +#include ompl_interface::TSStateStorage::TSStateStorage(const moveit::core::RobotModelPtr& robot_model) : start_state_(robot_model) diff --git a/moveit_planners/ompl/ompl_interface/src/model_based_planning_context.cpp b/moveit_planners/ompl/ompl_interface/src/model_based_planning_context.cpp index dca38f7da8..ebe1f0dc31 100644 --- a/moveit_planners/ompl/ompl_interface/src/model_based_planning_context.cpp +++ b/moveit_planners/ompl/ompl_interface/src/model_based_planning_context.cpp @@ -39,17 +39,17 @@ #include #include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include -#include +#include -#include +#include #include #include diff --git a/moveit_planners/ompl/ompl_interface/src/ompl_interface.cpp b/moveit_planners/ompl/ompl_interface/src/ompl_interface.cpp index cc34c91f85..a52e381080 100644 --- a/moveit_planners/ompl/ompl_interface/src/ompl_interface.cpp +++ b/moveit_planners/ompl/ompl_interface/src/ompl_interface.cpp @@ -34,10 +34,10 @@ /* Author: Ioan Sucan */ -#include -#include -#include -#include +#include +#include +#include +#include #include #include diff --git a/moveit_planners/ompl/ompl_interface/src/ompl_planner_manager.cpp b/moveit_planners/ompl/ompl_interface/src/ompl_planner_manager.cpp index 7daef874b5..e4675820fc 100644 --- a/moveit_planners/ompl/ompl_interface/src/ompl_planner_manager.cpp +++ b/moveit_planners/ompl/ompl_interface/src/ompl_planner_manager.cpp @@ -34,9 +34,9 @@ /* Author: Ioan Sucan, Dave Coleman */ -#include -#include -#include +#include +#include +#include #include #include diff --git a/moveit_planners/ompl/ompl_interface/src/parameterization/joint_space/constrained_planning_state_space.cpp b/moveit_planners/ompl/ompl_interface/src/parameterization/joint_space/constrained_planning_state_space.cpp index f00efdc5f5..ecb54eee3c 100644 --- a/moveit_planners/ompl/ompl_interface/src/parameterization/joint_space/constrained_planning_state_space.cpp +++ b/moveit_planners/ompl/ompl_interface/src/parameterization/joint_space/constrained_planning_state_space.cpp @@ -34,7 +34,7 @@ /* Author: Jeroen De Maeyer */ -#include +#include #include diff --git a/moveit_planners/ompl/ompl_interface/src/parameterization/joint_space/constrained_planning_state_space_factory.cpp b/moveit_planners/ompl/ompl_interface/src/parameterization/joint_space/constrained_planning_state_space_factory.cpp index 7830f81c37..a762dd6b2a 100644 --- a/moveit_planners/ompl/ompl_interface/src/parameterization/joint_space/constrained_planning_state_space_factory.cpp +++ b/moveit_planners/ompl/ompl_interface/src/parameterization/joint_space/constrained_planning_state_space_factory.cpp @@ -35,8 +35,8 @@ /* Author: Jeroen De Maeyer */ /* Mostly copied from Ioan Sucan's code */ -#include -#include +#include +#include namespace ompl_interface { diff --git a/moveit_planners/ompl/ompl_interface/src/parameterization/joint_space/joint_model_state_space.cpp b/moveit_planners/ompl/ompl_interface/src/parameterization/joint_space/joint_model_state_space.cpp index 8182da68f5..9ba095d420 100644 --- a/moveit_planners/ompl/ompl_interface/src/parameterization/joint_space/joint_model_state_space.cpp +++ b/moveit_planners/ompl/ompl_interface/src/parameterization/joint_space/joint_model_state_space.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include +#include const std::string ompl_interface::JointModelStateSpace::PARAMETERIZATION_TYPE = "JointModel"; diff --git a/moveit_planners/ompl/ompl_interface/src/parameterization/joint_space/joint_model_state_space_factory.cpp b/moveit_planners/ompl/ompl_interface/src/parameterization/joint_space/joint_model_state_space_factory.cpp index 85f54e8c3f..608f915283 100644 --- a/moveit_planners/ompl/ompl_interface/src/parameterization/joint_space/joint_model_state_space_factory.cpp +++ b/moveit_planners/ompl/ompl_interface/src/parameterization/joint_space/joint_model_state_space_factory.cpp @@ -34,8 +34,8 @@ /* Author: Ioan Sucan */ -#include -#include +#include +#include ompl_interface::JointModelStateSpaceFactory::JointModelStateSpaceFactory() : ModelBasedStateSpaceFactory() { diff --git a/moveit_planners/ompl/ompl_interface/src/parameterization/model_based_state_space.cpp b/moveit_planners/ompl/ompl_interface/src/parameterization/model_based_state_space.cpp index 4482e781d4..f0110fcc22 100644 --- a/moveit_planners/ompl/ompl_interface/src/parameterization/model_based_state_space.cpp +++ b/moveit_planners/ompl/ompl_interface/src/parameterization/model_based_state_space.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include +#include #include #include diff --git a/moveit_planners/ompl/ompl_interface/src/parameterization/model_based_state_space_factory.cpp b/moveit_planners/ompl/ompl_interface/src/parameterization/model_based_state_space_factory.cpp index 1a3158654b..5b9bcc678e 100644 --- a/moveit_planners/ompl/ompl_interface/src/parameterization/model_based_state_space_factory.cpp +++ b/moveit_planners/ompl/ompl_interface/src/parameterization/model_based_state_space_factory.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include +#include ompl_interface::ModelBasedStateSpacePtr ompl_interface::ModelBasedStateSpaceFactory::getNewStateSpace(const ModelBasedStateSpaceSpecification& space_spec) const diff --git a/moveit_planners/ompl/ompl_interface/src/parameterization/work_space/pose_model_state_space.cpp b/moveit_planners/ompl/ompl_interface/src/parameterization/work_space/pose_model_state_space.cpp index 600e5281de..ff569ab591 100644 --- a/moveit_planners/ompl/ompl_interface/src/parameterization/work_space/pose_model_state_space.cpp +++ b/moveit_planners/ompl/ompl_interface/src/parameterization/work_space/pose_model_state_space.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include +#include #include #include diff --git a/moveit_planners/ompl/ompl_interface/src/parameterization/work_space/pose_model_state_space_factory.cpp b/moveit_planners/ompl/ompl_interface/src/parameterization/work_space/pose_model_state_space_factory.cpp index 953b9382f3..b581c6d732 100644 --- a/moveit_planners/ompl/ompl_interface/src/parameterization/work_space/pose_model_state_space_factory.cpp +++ b/moveit_planners/ompl/ompl_interface/src/parameterization/work_space/pose_model_state_space_factory.cpp @@ -34,8 +34,8 @@ /* Author: Ioan Sucan */ -#include -#include +#include +#include ompl_interface::PoseModelStateSpaceFactory::PoseModelStateSpaceFactory() : ModelBasedStateSpaceFactory() { diff --git a/moveit_planners/ompl/ompl_interface/src/planning_context_manager.cpp b/moveit_planners/ompl/ompl_interface/src/planning_context_manager.cpp index bedd813c48..8da1bb4c7f 100644 --- a/moveit_planners/ompl/ompl_interface/src/planning_context_manager.cpp +++ b/moveit_planners/ompl/ompl_interface/src/planning_context_manager.cpp @@ -34,8 +34,8 @@ /* Author: Ioan Sucan */ -#include -#include +#include +#include #include #include @@ -71,12 +71,12 @@ #include #include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include using namespace std::placeholders; diff --git a/moveit_planners/ompl/ompl_interface/test/load_test_robot.h b/moveit_planners/ompl/ompl_interface/test/load_test_robot.h index 6ae825d265..96d1aebb51 100644 --- a/moveit_planners/ompl/ompl_interface/test/load_test_robot.h +++ b/moveit_planners/ompl/ompl_interface/test/load_test_robot.h @@ -35,9 +35,9 @@ /* Author: Jeroen De Maeyer */ #pragma once -#include -#include -#include +#include +#include +#include #include namespace ompl_interface_testing @@ -61,7 +61,7 @@ namespace ompl_interface_testing * --- example.cpp --- * * #include - * #include "load_test_robot.h" + * #include "load_test_robot.hpp" * * class GenericTests : public ompl_interface_testing::LoadTestRobot, public testing::Test * { diff --git a/moveit_planners/ompl/ompl_interface/test/test_constrained_planning_state_space.cpp b/moveit_planners/ompl/ompl_interface/test/test_constrained_planning_state_space.cpp index 223ba97f10..558f03aba6 100644 --- a/moveit_planners/ompl/ompl_interface/test/test_constrained_planning_state_space.cpp +++ b/moveit_planners/ompl/ompl_interface/test/test_constrained_planning_state_space.cpp @@ -45,11 +45,11 @@ #include #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include #include diff --git a/moveit_planners/ompl/ompl_interface/test/test_constrained_state_validity_checker.cpp b/moveit_planners/ompl/ompl_interface/test/test_constrained_state_validity_checker.cpp index bdb5676551..7a243fce0f 100644 --- a/moveit_planners/ompl/ompl_interface/test/test_constrained_state_validity_checker.cpp +++ b/moveit_planners/ompl/ompl_interface/test/test_constrained_state_validity_checker.cpp @@ -35,17 +35,17 @@ /* Author: Jeroen De Maeyer */ -#include "load_test_robot.h" +#include "load_test_robot.hpp" #include #include #include -#include -#include -#include -#include +#include +#include +#include +#include #include #include diff --git a/moveit_planners/ompl/ompl_interface/test/test_ompl_constraints.cpp b/moveit_planners/ompl/ompl_interface/test/test_ompl_constraints.cpp index 9ea14c5afb..5ea926c3e5 100644 --- a/moveit_planners/ompl/ompl_interface/test/test_ompl_constraints.cpp +++ b/moveit_planners/ompl/ompl_interface/test/test_ompl_constraints.cpp @@ -50,11 +50,11 @@ #include #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include #include diff --git a/moveit_planners/ompl/ompl_interface/test/test_planning_context_manager.cpp b/moveit_planners/ompl/ompl_interface/test/test_planning_context_manager.cpp index d4fb36a1f9..dfafe33f6f 100644 --- a/moveit_planners/ompl/ompl_interface/test/test_planning_context_manager.cpp +++ b/moveit_planners/ompl/ompl_interface/test/test_planning_context_manager.cpp @@ -56,14 +56,14 @@ #include -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include #include /** \brief Generic implementation of the tests that can be executed on different robots. **/ diff --git a/moveit_planners/ompl/ompl_interface/test/test_state_space.cpp b/moveit_planners/ompl/ompl_interface/test/test_state_space.cpp index 72568adc20..3089a31fbc 100644 --- a/moveit_planners/ompl/ompl_interface/test/test_state_space.cpp +++ b/moveit_planners/ompl/ompl_interface/test/test_state_space.cpp @@ -36,14 +36,14 @@ #include -#include -#include +#include +#include #include #include -#include -#include +#include +#include #include #include #include diff --git a/moveit_planners/ompl/ompl_interface/test/test_state_validity_checker.cpp b/moveit_planners/ompl/ompl_interface/test/test_state_validity_checker.cpp index 926c80b2fa..b62f59bd05 100644 --- a/moveit_planners/ompl/ompl_interface/test/test_state_validity_checker.cpp +++ b/moveit_planners/ompl/ompl_interface/test/test_state_validity_checker.cpp @@ -55,10 +55,10 @@ #include -#include -#include -#include -#include +#include +#include +#include +#include #include #include diff --git a/moveit_planners/ompl/ompl_interface/test/test_threadsafe_state_storage.cpp b/moveit_planners/ompl/ompl_interface/test/test_threadsafe_state_storage.cpp index 8034a69db2..6c642610d0 100644 --- a/moveit_planners/ompl/ompl_interface/test/test_threadsafe_state_storage.cpp +++ b/moveit_planners/ompl/ompl_interface/test/test_threadsafe_state_storage.cpp @@ -39,7 +39,7 @@ The skeleton of this test was taken from test_state_validity_checker.cpp by Jero */ #include "load_test_robot.hpp" -#include +#include #include /** \brief Generic implementation of the tests that can be executed on different robots. **/ diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h index 9c19a0be04..a3a64b6dfe 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h @@ -39,14 +39,14 @@ #include #include -#include -#include +#include +#include #include #include -#include -#include -#include +#include +#include +#include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h index 87b6ac8223..da245238cd 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h @@ -34,14 +34,14 @@ #pragma once -#include -#include +#include +#include #include -#include -#include -#include +#include +#include +#include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h index fb5e47bdab..912015c832 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h @@ -34,7 +34,7 @@ #pragma once -#include +#include #include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h index d73caaed60..ab3d1dea7d 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h @@ -34,7 +34,7 @@ #pragma once -#include +#include #include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h index 1911cf3943..0a737a48e9 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h @@ -34,8 +34,8 @@ #pragma once -#include -#include +#include +#include namespace pilz_industrial_motion_planner { diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h index 5cdf967a63..e26a52e276 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h @@ -34,7 +34,7 @@ #pragma once -#include +#include #include #include "cartesian_limits_parameters.hpp" diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h index c52af305a5..f6a32d1719 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h @@ -37,7 +37,7 @@ #include #include -#include +#include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h index 19e4d1ad09..00d02b1333 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h @@ -36,7 +36,7 @@ #include -#include +#include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h index 92a725d8cf..535fbd9644 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h @@ -36,11 +36,11 @@ #include -#include -#include +#include +#include -#include -#include +#include +#include #include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h index ce59f2b202..787226925a 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h @@ -37,14 +37,14 @@ #include #include -#include -#include -#include - -#include -#include -#include -#include +#include +#include +#include + +#include +#include +#include +#include namespace pilz_industrial_motion_planner { diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h index 7597316717..0abba27e76 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h @@ -34,15 +34,15 @@ #pragma once -#include -#include +#include +#include #include -#include -#include -#include -#include +#include +#include +#include +#include #include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h index 85b21efc84..e0b975c6f0 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h @@ -34,18 +34,18 @@ #pragma once -#include +#include #include -#include -#include +#include +#include #include #include -#include -#include +#include +#include namespace pilz_industrial_motion_planner { diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h index 54b1594399..dcd3e1724d 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h @@ -32,18 +32,18 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include #include -#include -#include +#include +#include #include #include -#include -#include +#include +#include namespace pilz_industrial_motion_planner { diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h index becd62a9df..5d93a34d14 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h @@ -34,14 +34,14 @@ #pragma once -#include +#include #include #include -#include +#include -#include +#include namespace pilz_industrial_motion_planner { diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h index cf9a847243..ea3e171a04 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h @@ -34,9 +34,9 @@ #pragma once -#include +#include -#include +#include namespace pilz_industrial_motion_planner { diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h index 970e04af52..c0f7eecf7e 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h @@ -34,9 +34,9 @@ #pragma once -#include +#include -#include +#include namespace pilz_industrial_motion_planner { diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h index dfdf2b6efb..42e23df4d6 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h @@ -34,9 +34,9 @@ #pragma once -#include +#include -#include +#include namespace pilz_industrial_motion_planner { diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h index c62bda37bb..994020aad7 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h @@ -34,18 +34,18 @@ #pragma once -#include +#include #include -#include -#include +#include +#include #include #include -#include -#include +#include +#include namespace pilz_industrial_motion_planner { diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h index ac5f58a548..aaf17fa7bd 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h @@ -39,7 +39,7 @@ #include #include -#include +#include namespace pilz_industrial_motion_planner { diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h index 450f89fea5..c24dda5e2e 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h @@ -36,7 +36,7 @@ #include -#include +#include namespace pilz_industrial_motion_planner { diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h index 3f518e5737..4f3ce4e597 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h @@ -36,7 +36,7 @@ #include -#include +#include namespace pilz_industrial_motion_planner { diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h index 702cdaccd5..914b214d24 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h @@ -34,12 +34,12 @@ #pragma once -#include -#include -#include +#include +#include +#include -#include -#include +#include +#include namespace pilz_industrial_motion_planner { diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h index 705e1703f0..79672d8b00 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h @@ -34,12 +34,12 @@ #pragma once -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include namespace pilz_industrial_motion_planner { diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h index 0adf6d1385..1f898b4ea0 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h @@ -36,16 +36,16 @@ #include #include -#include -#include -#include +#include +#include +#include #include #include -#include +#include -#include -#include -#include +#include +#include +#include namespace pilz_industrial_motion_planner { diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h index 69debc2b98..c17bcc8be3 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h @@ -40,14 +40,14 @@ #include #include #include -#include -#include -#include - -#include -#include -#include -#include +#include +#include +#include + +#include +#include +#include +#include namespace pilz_industrial_motion_planner { diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h index ef4ab6c814..c73c89a5fa 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h @@ -37,9 +37,9 @@ #include #include #include -#include +#include -#include +#include namespace pilz_industrial_motion_planner { diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h index 61592e0794..3c301b61e3 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h @@ -36,10 +36,10 @@ #include #include -#include +#include -#include -#include +#include +#include namespace pilz_industrial_motion_planner { diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h index cc73ff4839..e57b128c60 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h @@ -34,12 +34,12 @@ #pragma once -#include +#include #include -#include -#include -#include +#include +#include +#include namespace pilz_industrial_motion_planner { diff --git a/moveit_planners/pilz_industrial_motion_planner/src/command_list_manager.cpp b/moveit_planners/pilz_industrial_motion_planner/src/command_list_manager.cpp index 36458d5423..d222dd1e7c 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/command_list_manager.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/command_list_manager.cpp @@ -32,7 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include #include #include @@ -40,15 +40,15 @@ #include #include -#include -#include +#include +#include #include #include "cartesian_limits_parameters.hpp" -#include -#include -#include -#include +#include +#include +#include +#include namespace pilz_industrial_motion_planner { diff --git a/moveit_planners/pilz_industrial_motion_planner/src/joint_limits_aggregator.cpp b/moveit_planners/pilz_industrial_motion_planner/src/joint_limits_aggregator.cpp index e0bec40209..61a8655f86 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/joint_limits_aggregator.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/joint_limits_aggregator.cpp @@ -32,11 +32,11 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include -#include +#include +#include -#include -#include +#include +#include #include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/src/joint_limits_container.cpp b/moveit_planners/pilz_industrial_motion_planner/src/joint_limits_container.cpp index 55127d0334..1422a271d8 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/joint_limits_container.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/joint_limits_container.cpp @@ -32,7 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include #include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/src/joint_limits_validator.cpp b/moveit_planners/pilz_industrial_motion_planner/src/joint_limits_validator.cpp index 42c6b51f88..fb6eef5015 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/joint_limits_validator.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/joint_limits_validator.cpp @@ -32,13 +32,13 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include -#include +#include +#include -#include -#include +#include +#include -#include +#include bool pilz_industrial_motion_planner::JointLimitsValidator::validateAllPositionLimitsEqual( const pilz_industrial_motion_planner::JointLimitsContainer& joint_limits) diff --git a/moveit_planners/pilz_industrial_motion_planner/src/limits_container.cpp b/moveit_planners/pilz_industrial_motion_planner/src/limits_container.cpp index b99fc6c1fb..48b6774364 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/limits_container.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/limits_container.cpp @@ -32,7 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include #include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/src/move_group_sequence_action.cpp b/moveit_planners/pilz_industrial_motion_planner/src/move_group_sequence_action.cpp index a8e04ab132..0c103766a3 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/move_group_sequence_action.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/move_group_sequence_action.cpp @@ -36,21 +36,21 @@ // Modified by Pilz GmbH & Co. KG -#include +#include #include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include #include -#include -#include +#include +#include namespace pilz_industrial_motion_planner { diff --git a/moveit_planners/pilz_industrial_motion_planner/src/move_group_sequence_service.cpp b/moveit_planners/pilz_industrial_motion_planner/src/move_group_sequence_service.cpp index 8233f0b67e..935fc19c15 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/move_group_sequence_service.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/move_group_sequence_service.cpp @@ -36,13 +36,13 @@ // Modified by Pilz GmbH & Co. KG -#include +#include -#include -#include -#include +#include +#include +#include -#include +#include #include namespace pilz_industrial_motion_planner diff --git a/moveit_planners/pilz_industrial_motion_planner/src/path_circle_generator.cpp b/moveit_planners/pilz_industrial_motion_planner/src/path_circle_generator.cpp index 27589d2bb2..2c4515d4e6 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/path_circle_generator.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/path_circle_generator.cpp @@ -32,7 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include namespace pilz_industrial_motion_planner { diff --git a/moveit_planners/pilz_industrial_motion_planner/src/pilz_industrial_motion_planner.cpp b/moveit_planners/pilz_industrial_motion_planner/src/pilz_industrial_motion_planner.cpp index 0bde5aa46f..fbf19bf372 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/pilz_industrial_motion_planner.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/pilz_industrial_motion_planner.cpp @@ -34,14 +34,14 @@ #include -#include +#include -#include -#include -#include +#include +#include +#include #include "cartesian_limits_parameters.hpp" -#include +#include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/src/plan_components_builder.cpp b/moveit_planners/pilz_industrial_motion_planner/src/plan_components_builder.cpp index 0513d22b49..2f84dde8d9 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/plan_components_builder.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/plan_components_builder.cpp @@ -32,11 +32,11 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include #include -#include +#include namespace pilz_industrial_motion_planner { diff --git a/moveit_planners/pilz_industrial_motion_planner/src/planning_context_loader.cpp b/moveit_planners/pilz_industrial_motion_planner/src/planning_context_loader.cpp index 7fa110d0f5..0d575fe496 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/planning_context_loader.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/planning_context_loader.cpp @@ -32,7 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include pilz_industrial_motion_planner::PlanningContextLoader::PlanningContextLoader() : limits_set_(false), model_set_(false) { diff --git a/moveit_planners/pilz_industrial_motion_planner/src/planning_context_loader_circ.cpp b/moveit_planners/pilz_industrial_motion_planner/src/planning_context_loader_circ.cpp index 7052088e2f..1ab4ab0471 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/planning_context_loader_circ.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/planning_context_loader_circ.cpp @@ -35,10 +35,10 @@ #include #include -#include -#include -#include -#include +#include +#include +#include +#include #include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/src/planning_context_loader_lin.cpp b/moveit_planners/pilz_industrial_motion_planner/src/planning_context_loader_lin.cpp index 7deb454f1d..a3c261f9be 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/planning_context_loader_lin.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/planning_context_loader_lin.cpp @@ -32,10 +32,10 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include -#include -#include -#include +#include +#include +#include +#include #include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/src/planning_context_loader_ptp.cpp b/moveit_planners/pilz_industrial_motion_planner/src/planning_context_loader_ptp.cpp index 429ec42657..905ee08237 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/planning_context_loader_ptp.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/planning_context_loader_ptp.cpp @@ -32,9 +32,9 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include -#include -#include +#include +#include +#include #include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_blender_transition_window.cpp b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_blender_transition_window.cpp index 84e6679709..41deb7ccd7 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_blender_transition_window.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_blender_transition_window.cpp @@ -32,13 +32,13 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include #include #include #include #include -#include +#include #include namespace diff --git a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_functions.cpp b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_functions.cpp index 7a4ea937bf..e4c5d6a4d8 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_functions.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_functions.cpp @@ -32,9 +32,9 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include -#include +#include #include #include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator.cpp b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator.cpp index 4b0482ca64..6f17fbc3a2 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator.cpp @@ -32,7 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include #include @@ -41,10 +41,10 @@ #include #include -#include +#include #include -#include +#include namespace pilz_industrial_motion_planner { diff --git a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator_circ.cpp b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator_circ.cpp index e0ef8ce126..4e92524bfc 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator_circ.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator_circ.cpp @@ -32,8 +32,8 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include -#include +#include +#include #include #include @@ -42,7 +42,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator_lin.cpp b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator_lin.cpp index cee73b29fa..4b51582099 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator_lin.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator_lin.cpp @@ -38,10 +38,12 @@ #include #include - +#include #include #include - +#include +#include +#include #include #include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator_ptp.cpp b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator_ptp.cpp index f7c45ac29a..6113b603eb 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator_ptp.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator_ptp.cpp @@ -32,8 +32,8 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include -#include +#include +#include #include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/src/velocity_profile_atrap.cpp b/moveit_planners/pilz_industrial_motion_planner/src/velocity_profile_atrap.cpp index 76d0354cf0..836845f1c2 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/velocity_profile_atrap.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/velocity_profile_atrap.cpp @@ -32,7 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include namespace pilz_industrial_motion_planner { diff --git a/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_command_list_manager.cpp b/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_command_list_manager.cpp index 2f0fb62c72..04d1f7403d 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_command_list_manager.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_command_list_manager.cpp @@ -41,23 +41,23 @@ #include #include -#include -#include -#include +#include +#include +#include #include #include #include -#include -#include -#include -#include +#include +#include +#include +#include #include "test_utils.hpp" -#include -#include +#include +#include const std::string ROBOT_DESCRIPTION_STR{ "robot_description" }; const std::string EMPTY_VALUE{ "" }; diff --git a/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_command_planning.cpp b/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_command_planning.cpp index abcab274cc..c32cd99ae7 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_command_planning.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_command_planning.cpp @@ -39,15 +39,15 @@ #include #include -#include -#include -#include -#include +#include +#include +#include +#include #include #include #include -#include -#include +#include +#include #include #include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_get_solver_tip_frame.cpp b/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_get_solver_tip_frame.cpp index e52c50d487..dc430eff0a 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_get_solver_tip_frame.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_get_solver_tip_frame.cpp @@ -39,12 +39,12 @@ #include -#include -#include -#include +#include +#include +#include #include -#include +#include static const std::string ROBOT_DESCRIPTION_PARAM{ "robot_description" }; diff --git a/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_plan_components_builder.cpp b/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_plan_components_builder.cpp index 498e743e6b..1fe6977944 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_plan_components_builder.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_plan_components_builder.cpp @@ -39,11 +39,11 @@ #include -#include -#include +#include +#include -#include -#include +#include +#include const std::string PARAM_PLANNING_GROUP_NAME("planning_group"); const std::string ROBOT_DESCRIPTION_STR{ "robot_description" }; diff --git a/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_sequence_action.cpp b/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_sequence_action.cpp index 1c55d013e3..81cd51dcd7 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_sequence_action.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_sequence_action.cpp @@ -43,20 +43,20 @@ #include #include -#include -#include -#include -#include +#include +#include +#include +#include #include #include #include #include -#include +#include -#include -#include -#include +#include +#include +#include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_sequence_action_preemption.cpp b/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_sequence_action_preemption.cpp index a160138445..6f8a481512 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_sequence_action_preemption.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_sequence_action_preemption.cpp @@ -43,21 +43,21 @@ #include #include -#include -#include -#include -#include +#include +#include +#include +#include #include #include #include #include #include -#include +#include -#include -#include -#include +#include +#include +#include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_sequence_service_capability.cpp b/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_sequence_service_capability.cpp index dd1d50a630..78fb4bf41e 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_sequence_service_capability.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/integration_tests/src/integrationtest_sequence_service_capability.cpp @@ -39,22 +39,22 @@ #include #include -#include -#include -#include -#include +#include +#include +#include +#include #include #include #include #include #include -#include -#include +#include +#include #include #include -#include +#include // Parameters from the node const std::string TEST_DATA_FILE_NAME("testdata_file_name"); diff --git a/moveit_planners/pilz_industrial_motion_planner/test/test_utils.cpp b/moveit_planners/pilz_industrial_motion_planner/test/test_utils.cpp index fca5e3b220..24acb2b0a2 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/test_utils.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/test_utils.cpp @@ -33,8 +33,8 @@ *********************************************************************/ #include -#include -#include +#include +#include #include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/test/test_utils.h b/moveit_planners/pilz_industrial_motion_planner/test/test_utils.h index 758c5ecada..87c2d319ab 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/test_utils.h +++ b/moveit_planners/pilz_industrial_motion_planner/test/test_utils.h @@ -43,15 +43,15 @@ #endif #include -#include -#include -#include -#include +#include +#include +#include +#include #include #include -#include -#include -#include +#include +#include +#include #include #include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_get_solver_tip_frame.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_get_solver_tip_frame.cpp index 110f67b418..8973e71962 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_get_solver_tip_frame.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_get_solver_tip_frame.cpp @@ -40,9 +40,9 @@ #include #include -#include +#include -#include +#include namespace pilz_industrial_motion_planner { diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_joint_limit.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_joint_limit.cpp index 6c2bb24522..3992ea7fb3 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_joint_limit.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_joint_limit.cpp @@ -36,8 +36,8 @@ #include -#include -#include +#include +#include using namespace pilz_industrial_motion_planner; using namespace pilz_industrial_motion_planner::joint_limits_interface; diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_joint_limits_aggregator.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_joint_limits_aggregator.cpp index cdf7002625..eab1e99ae3 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_joint_limits_aggregator.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_joint_limits_aggregator.cpp @@ -34,12 +34,12 @@ #include -#include -#include +#include +#include -#include -#include -#include +#include +#include +#include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_joint_limits_container.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_joint_limits_container.cpp index 0a4ce0d7ec..4977106928 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_joint_limits_container.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_joint_limits_container.cpp @@ -34,8 +34,8 @@ #include -#include -#include +#include +#include using namespace pilz_industrial_motion_planner; diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_joint_limits_validator.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_joint_limits_validator.cpp index 8ff46d3dcf..e421e52437 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_joint_limits_validator.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_joint_limits_validator.cpp @@ -34,9 +34,9 @@ #include -#include +#include -#include +#include using namespace pilz_industrial_motion_planner; diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_pilz_industrial_motion_planner.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_pilz_industrial_motion_planner.cpp index 2d0109f1e5..33f9e2dc31 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_pilz_industrial_motion_planner.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_pilz_industrial_motion_planner.cpp @@ -36,10 +36,10 @@ #include -#include -#include +#include +#include -#include +#include #include "test_utils.hpp" #include diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_pilz_industrial_motion_planner_direct.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_pilz_industrial_motion_planner_direct.cpp index cb22d36d50..db67c3c6b9 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_pilz_industrial_motion_planner_direct.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_pilz_industrial_motion_planner_direct.cpp @@ -36,9 +36,9 @@ #include -#include -#include -#include +#include +#include +#include using namespace pilz_industrial_motion_planner; diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context.cpp index 232f866092..48dfe23752 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context.cpp @@ -35,17 +35,17 @@ #include #include -#include +#include -#include -#include -#include -#include +#include +#include +#include +#include -#include -#include -#include -#include +#include +#include +#include +#include #include "test_utils.hpp" diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context_loaders.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context_loaders.cpp index 8dc23da3c0..57d75e9241 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context_loaders.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context_loaders.cpp @@ -36,10 +36,10 @@ #include -#include -#include +#include +#include -#include +#include #include "test_utils.hpp" diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_blender_transition_window.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_blender_transition_window.cpp index c3d524256d..63f65f9903 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_blender_transition_window.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_blender_transition_window.cpp @@ -36,22 +36,22 @@ #include -#include -#include -#include -#include +#include +#include +#include +#include #include #include -#include -#include -#include +#include +#include +#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include "test_utils.hpp" #include diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_functions.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_functions.cpp index 5bfaba862e..63f2783aeb 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_functions.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_functions.cpp @@ -46,17 +46,17 @@ #include #include #include -#include -#include -#include -#include +#include +#include +#include +#include #include #include -#include -#include -#include -#include +#include +#include +#include +#include #include "test_utils.hpp" #define _USE_MATH_DEFINES diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_generator.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_generator.cpp index dafd6fa535..3a495456f0 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_generator.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_generator.cpp @@ -36,7 +36,7 @@ #include -#include +#include using namespace pilz_industrial_motion_planner; diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_generator_circ.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_generator_circ.cpp index 5c9ba0b4b0..33fdb0af0e 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_generator_circ.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_generator_circ.cpp @@ -36,17 +36,17 @@ #include -#include -#include -#include -#include +#include +#include +#include +#include #include #include -#include -#include -#include -#include +#include +#include +#include +#include #include "test_utils.hpp" #include diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_generator_common.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_generator_common.cpp index 9db58f5ede..fbc31afa11 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_generator_common.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_generator_common.cpp @@ -35,21 +35,21 @@ #include #include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include - -#include "test_utils.h" +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include "test_utils.hpp" #include diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_generator_lin.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_generator_lin.cpp index 77ebfd0b8b..6f049ed9a4 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_generator_lin.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_generator_lin.cpp @@ -36,17 +36,17 @@ #include -#include -#include -#include -#include +#include +#include +#include +#include #include "test_utils.hpp" -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_velocity_profile_atrap.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_velocity_profile_atrap.cpp index 0fa4317ae7..8140c25112 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_velocity_profile_atrap.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_velocity_profile_atrap.cpp @@ -34,7 +34,7 @@ #include -#include +#include // Modultest Level1 of Class VelocityProfileATrap #define EPSILON 1.0e-10 diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h index 480a5d55ef..e9ff450c64 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h @@ -40,10 +40,10 @@ #include #include -#include -#include -#include -#include +#include +#include +#include +#include #include "robotconfiguration.hpp" #include "jointconfiguration.hpp" diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h index 128564b304..2a9ec854bd 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h @@ -35,7 +35,7 @@ #pragma once #include -#include +#include namespace pilz_industrial_motion_planner_testutils { diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h index dd4a03d07d..a27ca8210f 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h @@ -37,7 +37,7 @@ #include #include -#include +#include namespace pilz_industrial_motion_planner_testutils { diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h index 29ca954184..efeff7fb51 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h @@ -34,7 +34,7 @@ #pragma once -#include "circauxiliary.h" +#include "circauxiliary.hpp" namespace pilz_industrial_motion_planner_testutils { diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h index 2daf37f92e..c016f8ec4f 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h @@ -41,10 +41,10 @@ #include #include -#include -#include +#include +#include -#include "robotconfiguration.h" +#include "robotconfiguration.hpp" namespace pilz_industrial_motion_planner_testutils { diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h index 9d5f250faa..46fab92ce6 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h @@ -36,7 +36,7 @@ #include -#include "basecmd.h" +#include "basecmd.hpp" namespace pilz_industrial_motion_planner_testutils { diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h index 54c6d9456e..8c1064bb10 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h @@ -37,7 +37,7 @@ #include #include -#include "motionplanrequestconvertible.h" +#include "motionplanrequestconvertible.hpp" namespace pilz_industrial_motion_planner_testutils { diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h index 3b3d9046cd..8503429d0a 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h @@ -34,8 +34,8 @@ #pragma once -#include -#include +#include +#include namespace pilz_industrial_motion_planner_testutils { diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h index 04dab225d9..951161d7ff 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h @@ -36,7 +36,7 @@ #include -#include "basecmd.h" +#include "basecmd.hpp" namespace pilz_industrial_motion_planner_testutils { diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h index 07fd1c545b..f96e61cd52 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h @@ -37,10 +37,10 @@ #include #include -#include +#include -#include "goalconstraintsmsgconvertible.h" -#include "robotstatemsgconvertible.h" +#include "goalconstraintsmsgconvertible.hpp" +#include "robotstatemsgconvertible.hpp" namespace pilz_industrial_motion_planner_testutils { diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h index 7e9da57924..89d1d3cc66 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h @@ -35,7 +35,7 @@ #pragma once #include -#include +#include namespace pilz_industrial_motion_planner_testutils { diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h index e18d517080..18477b4615 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h @@ -41,8 +41,8 @@ #include -#include "command_types_typedef.h" -#include "motioncmd.h" +#include "command_types_typedef.hpp" +#include "motioncmd.hpp" #include namespace pilz_industrial_motion_planner_testutils diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h index 10ea232571..ca596e5757 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h @@ -37,13 +37,13 @@ #include #include -#include +#include -#include "jointconfiguration.h" -#include "cartesianconfiguration.h" -#include "command_types_typedef.h" -#include "sequence.h" -#include "gripper.h" +#include "jointconfiguration.hpp" +#include "cartesianconfiguration.hpp" +#include "command_types_typedef.hpp" +#include "sequence.hpp" +#include "gripper.hpp" namespace pilz_industrial_motion_planner_testutils { diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h index 213c11a321..3e2baa5bd3 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h @@ -42,7 +42,7 @@ #include -#include +#include namespace pt = boost::property_tree; namespace pilz_industrial_motion_planner_testutils diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/src/cartesianconfiguration.cpp b/moveit_planners/pilz_industrial_motion_planner_testutils/src/cartesianconfiguration.cpp index 3cd8c9f9d4..9c4a6da560 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/src/cartesianconfiguration.cpp +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/src/cartesianconfiguration.cpp @@ -32,7 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include #include #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/src/jointconfiguration.cpp b/moveit_planners/pilz_industrial_motion_planner_testutils/src/jointconfiguration.cpp index feedad72e1..6f53bdc91f 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/src/jointconfiguration.cpp +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/src/jointconfiguration.cpp @@ -32,9 +32,9 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include -#include +#include namespace pilz_industrial_motion_planner_testutils { diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/src/robotconfiguration.cpp b/moveit_planners/pilz_industrial_motion_planner_testutils/src/robotconfiguration.cpp index b267f725ee..35b49e987f 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/src/robotconfiguration.cpp +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/src/robotconfiguration.cpp @@ -32,7 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/src/sequence.cpp b/moveit_planners/pilz_industrial_motion_planner_testutils/src/sequence.cpp index e449b14e2a..e914b73cd3 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/src/sequence.cpp +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/src/sequence.cpp @@ -32,7 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/src/xml_testdata_loader.cpp b/moveit_planners/pilz_industrial_motion_planner_testutils/src/xml_testdata_loader.cpp index 4f775d678e..7240a0da7a 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/src/xml_testdata_loader.cpp +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/src/xml_testdata_loader.cpp @@ -32,16 +32,16 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include #include #include #include -#include -#include -#include +#include +#include +#include namespace pt = boost::property_tree; namespace pilz_industrial_motion_planner_testutils diff --git a/moveit_planners/stomp/include/stomp_moveit/conversion_functions.hpp b/moveit_planners/stomp/include/stomp_moveit/conversion_functions.hpp index 20c5d83773..f4a94824ad 100644 --- a/moveit_planners/stomp/include/stomp_moveit/conversion_functions.hpp +++ b/moveit_planners/stomp/include/stomp_moveit/conversion_functions.hpp @@ -39,8 +39,8 @@ #pragma once -#include -#include +#include +#include namespace stomp_moveit { diff --git a/moveit_planners/stomp/include/stomp_moveit/cost_functions.hpp b/moveit_planners/stomp/include/stomp_moveit/cost_functions.hpp index 705f796cba..b910cd3393 100644 --- a/moveit_planners/stomp/include/stomp_moveit/cost_functions.hpp +++ b/moveit_planners/stomp/include/stomp_moveit/cost_functions.hpp @@ -41,8 +41,8 @@ #include -#include -#include +#include +#include #include #include diff --git a/moveit_planners/stomp/include/stomp_moveit/filter_functions.hpp b/moveit_planners/stomp/include/stomp_moveit/filter_functions.hpp index f1ec47b3bb..fe4006a32c 100644 --- a/moveit_planners/stomp/include/stomp_moveit/filter_functions.hpp +++ b/moveit_planners/stomp/include/stomp_moveit/filter_functions.hpp @@ -40,7 +40,7 @@ #pragma once #include -#include +#include #include #include diff --git a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.hpp b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.hpp index e7a33c5aec..a5add5e515 100644 --- a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.hpp +++ b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.hpp @@ -39,7 +39,7 @@ #pragma once -#include +#include #include diff --git a/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.hpp b/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.hpp index 518f73c855..2bea61fcda 100644 --- a/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.hpp +++ b/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.hpp @@ -42,8 +42,8 @@ #include #include -#include -#include +#include +#include #include #include #include diff --git a/moveit_planners/stomp/src/stomp_moveit_planning_context.cpp b/moveit_planners/stomp/src/stomp_moveit_planning_context.cpp index de5d43a6ff..4d37e61de6 100644 --- a/moveit_planners/stomp/src/stomp_moveit_planning_context.cpp +++ b/moveit_planners/stomp/src/stomp_moveit_planning_context.cpp @@ -49,8 +49,8 @@ #include #include -#include -#include +#include +#include #include namespace stomp_moveit diff --git a/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/src/prbt_manipulator_ikfast_solver.cpp b/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/src/prbt_manipulator_ikfast_solver.cpp index 8741aa7cce..207f1f12bb 100644 --- a/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/src/prbt_manipulator_ikfast_solver.cpp +++ b/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/src/prbt_manipulator_ikfast_solver.cpp @@ -22,7 +22,7 @@ /// To compile without any main function as a shared object (might need -llapack): /// gcc -fPIC -lstdc++ -DIKFAST_NO_MAIN -DIKFAST_CLIBRARY -shared -Wl,-soname,libik.so -o libik.so ik.cpp #define IKFAST_HAS_LIBRARY -#include "ikfast.h" // found inside share/openrave-X.Y/python/ikfast.h +#include "ikfast.hpp" // found inside share/openrave-X.Y/python/ikfast.h using namespace ikfast; // check if the included ikfast version matches what this file was compiled with diff --git a/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h b/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h index 37454204c5..f44229a4b3 100644 --- a/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h +++ b/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include namespace moveit_ros_control_interface { diff --git a/moveit_plugins/moveit_ros_control_interface/src/controller_manager_plugin.cpp b/moveit_plugins/moveit_ros_control_interface/src/controller_manager_plugin.cpp index eb7b2e8205..42d5378d0e 100644 --- a/moveit_plugins/moveit_ros_control_interface/src/controller_manager_plugin.cpp +++ b/moveit_plugins/moveit_ros_control_interface/src/controller_manager_plugin.cpp @@ -34,10 +34,10 @@ /* Author: Mathias Lüdtke */ -#include -#include -#include -#include +#include +#include +#include +#include #include #include #include diff --git a/moveit_plugins/moveit_ros_control_interface/src/empty_controller_plugin.cpp b/moveit_plugins/moveit_ros_control_interface/src/empty_controller_plugin.cpp index 0b2887031b..a8e23607d6 100644 --- a/moveit_plugins/moveit_ros_control_interface/src/empty_controller_plugin.cpp +++ b/moveit_plugins/moveit_ros_control_interface/src/empty_controller_plugin.cpp @@ -35,7 +35,7 @@ /* Author: Paul Gesel */ #include -#include +#include #include namespace moveit_ros_control_interface diff --git a/moveit_plugins/moveit_ros_control_interface/src/gripper_controller_plugin.cpp b/moveit_plugins/moveit_ros_control_interface/src/gripper_controller_plugin.cpp index d7e213a52a..8d6e9fafad 100644 --- a/moveit_plugins/moveit_ros_control_interface/src/gripper_controller_plugin.cpp +++ b/moveit_plugins/moveit_ros_control_interface/src/gripper_controller_plugin.cpp @@ -34,9 +34,9 @@ /* Author: Joseph Schornak */ -#include +#include #include -#include +#include #include #include diff --git a/moveit_plugins/moveit_ros_control_interface/src/joint_trajectory_controller_plugin.cpp b/moveit_plugins/moveit_ros_control_interface/src/joint_trajectory_controller_plugin.cpp index 6ad36fbd90..048d3edec3 100644 --- a/moveit_plugins/moveit_ros_control_interface/src/joint_trajectory_controller_plugin.cpp +++ b/moveit_plugins/moveit_ros_control_interface/src/joint_trajectory_controller_plugin.cpp @@ -34,9 +34,9 @@ /* Author: Mathias Lüdtke */ -#include +#include #include -#include +#include #include #include diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h index 72213aa0cc..cce6cc991a 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h @@ -39,8 +39,8 @@ #include #include -#include -#include +#include +#include #include namespace moveit_simple_controller_manager diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h index 48f4cc93a6..a65b8e8b75 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h @@ -36,7 +36,7 @@ #pragma once -#include +#include #include namespace moveit_simple_controller_manager diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h index 70ae825680..6327784fc7 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h @@ -37,7 +37,7 @@ #pragma once -#include +#include #include #include #include diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h index 42f9b8a976..6f2dc9a21b 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h @@ -37,7 +37,7 @@ #pragma once -#include +#include #include #include diff --git a/moveit_plugins/moveit_simple_controller_manager/src/follow_joint_trajectory_controller_handle.cpp b/moveit_plugins/moveit_simple_controller_manager/src/follow_joint_trajectory_controller_handle.cpp index c7b49e0751..17afae2a80 100644 --- a/moveit_plugins/moveit_simple_controller_manager/src/follow_joint_trajectory_controller_handle.cpp +++ b/moveit_plugins/moveit_simple_controller_manager/src/follow_joint_trajectory_controller_handle.cpp @@ -35,7 +35,7 @@ /* Author: Michael Ferguson, Ioan Sucan, E. Gil Jones */ -#include +#include using namespace std::placeholders; diff --git a/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager.cpp b/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager.cpp index 40af565902..394765c8cb 100644 --- a/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager.cpp +++ b/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager.cpp @@ -35,9 +35,9 @@ /* Author: Michael Ferguson, Ioan Sucan, E. Gil Jones */ -#include -#include -#include +#include +#include +#include #include #include #include diff --git a/moveit_py/src/moveit/core.cpp b/moveit_py/src/moveit/core.cpp index 652a442c01..e65f2b1caa 100644 --- a/moveit_py/src/moveit/core.cpp +++ b/moveit_py/src/moveit/core.cpp @@ -34,18 +34,18 @@ /* Author: Peter David Fagan */ -#include "moveit_core/collision_detection/collision_common.h" -#include "moveit_core/collision_detection/collision_matrix.h" -#include "moveit_core/collision_detection/world.h" -#include "moveit_core/controller_manager/controller_manager.h" -#include "moveit_core/kinematic_constraints/utils.h" -#include "moveit_core/planning_interface/planning_response.h" -#include "moveit_core/planning_scene/planning_scene.h" -#include "moveit_core/robot_model/joint_model.h" -#include "moveit_core/robot_model/joint_model_group.h" -#include "moveit_core/robot_model/robot_model.h" -#include "moveit_core/robot_state/robot_state.h" -#include "moveit_core/robot_trajectory/robot_trajectory.h" +#include "moveit_core/collision_detection/collision_common.hpp" +#include "moveit_core/collision_detection/collision_matrix.hpp" +#include "moveit_core/collision_detection/world.hpp" +#include "moveit_core/controller_manager/controller_manager.hpp" +#include "moveit_core/kinematic_constraints/utils.hpp" +#include "moveit_core/planning_interface/planning_response.hpp" +#include "moveit_core/planning_scene/planning_scene.hpp" +#include "moveit_core/robot_model/joint_model.hpp" +#include "moveit_core/robot_model/joint_model_group.hpp" +#include "moveit_core/robot_model/robot_model.hpp" +#include "moveit_core/robot_state/robot_state.hpp" +#include "moveit_core/robot_trajectory/robot_trajectory.hpp" PYBIND11_MODULE(core, m) { diff --git a/moveit_py/src/moveit/moveit_core/collision_detection/collision_common.cpp b/moveit_py/src/moveit/moveit_core/collision_detection/collision_common.cpp index 6125fa71af..f5744a980d 100644 --- a/moveit_py/src/moveit/moveit_core/collision_detection/collision_common.cpp +++ b/moveit_py/src/moveit/moveit_core/collision_detection/collision_common.cpp @@ -34,7 +34,7 @@ /* Author: Peter David Fagan */ -#include "collision_common.h" +#include "collision_common.hpp" namespace moveit_py { diff --git a/moveit_py/src/moveit/moveit_core/collision_detection/collision_common.h b/moveit_py/src/moveit/moveit_core/collision_detection/collision_common.h index 63af366183..eab1c1113e 100644 --- a/moveit_py/src/moveit/moveit_core/collision_detection/collision_common.h +++ b/moveit_py/src/moveit/moveit_core/collision_detection/collision_common.h @@ -37,7 +37,7 @@ #include #include #include -#include +#include namespace py = pybind11; diff --git a/moveit_py/src/moveit/moveit_core/collision_detection/collision_matrix.cpp b/moveit_py/src/moveit/moveit_core/collision_detection/collision_matrix.cpp index b0ea225050..c3be69f620 100644 --- a/moveit_py/src/moveit/moveit_core/collision_detection/collision_matrix.cpp +++ b/moveit_py/src/moveit/moveit_core/collision_detection/collision_matrix.cpp @@ -34,7 +34,7 @@ /* Author: Peter David Fagan */ -#include "collision_matrix.h" +#include "collision_matrix.hpp" namespace moveit_py { diff --git a/moveit_py/src/moveit/moveit_core/collision_detection/collision_matrix.h b/moveit_py/src/moveit/moveit_core/collision_detection/collision_matrix.h index 68854c532d..f5bbecd912 100644 --- a/moveit_py/src/moveit/moveit_core/collision_detection/collision_matrix.h +++ b/moveit_py/src/moveit/moveit_core/collision_detection/collision_matrix.h @@ -37,7 +37,7 @@ #include #include #include -#include +#include namespace py = pybind11; diff --git a/moveit_py/src/moveit/moveit_core/collision_detection/world.cpp b/moveit_py/src/moveit/moveit_core/collision_detection/world.cpp index ee2e69cc62..37c3f54a7a 100644 --- a/moveit_py/src/moveit/moveit_core/collision_detection/world.cpp +++ b/moveit_py/src/moveit/moveit_core/collision_detection/world.cpp @@ -34,7 +34,7 @@ /* Author: Jafar Uruç */ -#include "world.h" +#include "world.hpp" namespace moveit_py { diff --git a/moveit_py/src/moveit/moveit_core/collision_detection/world.h b/moveit_py/src/moveit/moveit_core/collision_detection/world.h index 2dd0b8ef5b..544ac530cc 100644 --- a/moveit_py/src/moveit/moveit_core/collision_detection/world.h +++ b/moveit_py/src/moveit/moveit_core/collision_detection/world.h @@ -37,7 +37,7 @@ #include #include #include -#include +#include namespace py = pybind11; diff --git a/moveit_py/src/moveit/moveit_core/controller_manager/controller_manager.cpp b/moveit_py/src/moveit/moveit_core/controller_manager/controller_manager.cpp index ce9165ce0f..dffcb5550b 100644 --- a/moveit_py/src/moveit/moveit_core/controller_manager/controller_manager.cpp +++ b/moveit_py/src/moveit/moveit_core/controller_manager/controller_manager.cpp @@ -34,7 +34,7 @@ /* Author: Peter David Fagan */ -#include "controller_manager.h" +#include "controller_manager.hpp" namespace moveit_py { diff --git a/moveit_py/src/moveit/moveit_core/controller_manager/controller_manager.h b/moveit_py/src/moveit/moveit_core/controller_manager/controller_manager.h index 2fa5390292..d52926f30f 100644 --- a/moveit_py/src/moveit/moveit_core/controller_manager/controller_manager.h +++ b/moveit_py/src/moveit/moveit_core/controller_manager/controller_manager.h @@ -36,7 +36,7 @@ #pragma once -#include +#include #include #include #include diff --git a/moveit_py/src/moveit/moveit_core/kinematic_constraints/utils.cpp b/moveit_py/src/moveit/moveit_core/kinematic_constraints/utils.cpp index fa1ee2fea7..9f055cb289 100644 --- a/moveit_py/src/moveit/moveit_core/kinematic_constraints/utils.cpp +++ b/moveit_py/src/moveit/moveit_core/kinematic_constraints/utils.cpp @@ -34,10 +34,10 @@ /* Author: Peter David Fagan */ -#include "utils.h" +#include "utils.hpp" #include -#include -#include +#include +#include namespace moveit_py { diff --git a/moveit_py/src/moveit/moveit_core/kinematic_constraints/utils.h b/moveit_py/src/moveit/moveit_core/kinematic_constraints/utils.h index 161e3b03fa..355a80e978 100644 --- a/moveit_py/src/moveit/moveit_core/kinematic_constraints/utils.h +++ b/moveit_py/src/moveit/moveit_core/kinematic_constraints/utils.h @@ -38,7 +38,7 @@ #include #include #include -#include +#include #include namespace py = pybind11; diff --git a/moveit_py/src/moveit/moveit_core/planning_interface/planning_response.cpp b/moveit_py/src/moveit/moveit_core/planning_interface/planning_response.cpp index 8ebf5437f4..92119a1ff6 100644 --- a/moveit_py/src/moveit/moveit_core/planning_interface/planning_response.cpp +++ b/moveit_py/src/moveit/moveit_core/planning_interface/planning_response.cpp @@ -34,7 +34,7 @@ /* Author: Peter David Fagan */ -#include "planning_response.h" +#include "planning_response.hpp" namespace moveit_py { diff --git a/moveit_py/src/moveit/moveit_core/planning_interface/planning_response.h b/moveit_py/src/moveit/moveit_core/planning_interface/planning_response.h index 88943db5d6..fdbae99d9f 100644 --- a/moveit_py/src/moveit/moveit_core/planning_interface/planning_response.h +++ b/moveit_py/src/moveit/moveit_core/planning_interface/planning_response.h @@ -39,10 +39,10 @@ #include #include #include -#include -#include -#include -#include +#include +#include +#include +#include namespace py = pybind11; diff --git a/moveit_py/src/moveit/moveit_core/planning_scene/planning_scene.cpp b/moveit_py/src/moveit/moveit_core/planning_scene/planning_scene.cpp index e55b0f15d4..722b71eb91 100644 --- a/moveit_py/src/moveit/moveit_core/planning_scene/planning_scene.cpp +++ b/moveit_py/src/moveit/moveit_core/planning_scene/planning_scene.cpp @@ -34,8 +34,8 @@ /* Author: Peter David Fagan */ -#include "planning_scene.h" -#include +#include "planning_scene.hpp" +#include #include #include diff --git a/moveit_py/src/moveit/moveit_core/planning_scene/planning_scene.h b/moveit_py/src/moveit/moveit_core/planning_scene/planning_scene.h index 14a6d1ca1d..ac0b5e8355 100644 --- a/moveit_py/src/moveit/moveit_core/planning_scene/planning_scene.h +++ b/moveit_py/src/moveit/moveit_core/planning_scene/planning_scene.h @@ -39,9 +39,9 @@ #include #include #include -#include -#include -#include +#include +#include +#include namespace py = pybind11; diff --git a/moveit_py/src/moveit/moveit_core/robot_model/joint_model.cpp b/moveit_py/src/moveit/moveit_core/robot_model/joint_model.cpp index 7d335b0b7f..9428dc2e00 100644 --- a/moveit_py/src/moveit/moveit_core/robot_model/joint_model.cpp +++ b/moveit_py/src/moveit/moveit_core/robot_model/joint_model.cpp @@ -34,8 +34,8 @@ /* Author: Jafar Uruç */ -#include "joint_model.h" -#include +#include "joint_model.hpp" +#include namespace moveit_py { diff --git a/moveit_py/src/moveit/moveit_core/robot_model/joint_model.h b/moveit_py/src/moveit/moveit_core/robot_model/joint_model.h index bcd72d0171..4502593195 100644 --- a/moveit_py/src/moveit/moveit_core/robot_model/joint_model.h +++ b/moveit_py/src/moveit/moveit_core/robot_model/joint_model.h @@ -39,7 +39,7 @@ #include #include #include -#include +#include namespace py = pybind11; diff --git a/moveit_py/src/moveit/moveit_core/robot_model/joint_model_group.cpp b/moveit_py/src/moveit/moveit_core/robot_model/joint_model_group.cpp index 7d51171047..5325ee4159 100644 --- a/moveit_py/src/moveit/moveit_core/robot_model/joint_model_group.cpp +++ b/moveit_py/src/moveit/moveit_core/robot_model/joint_model_group.cpp @@ -34,7 +34,7 @@ /* Author: Peter David Fagan */ -#include "joint_model_group.h" +#include "joint_model_group.hpp" #include namespace moveit_py diff --git a/moveit_py/src/moveit/moveit_core/robot_model/joint_model_group.h b/moveit_py/src/moveit/moveit_core/robot_model/joint_model_group.h index be54b09e6a..95d91e3065 100644 --- a/moveit_py/src/moveit/moveit_core/robot_model/joint_model_group.h +++ b/moveit_py/src/moveit/moveit_core/robot_model/joint_model_group.h @@ -39,7 +39,7 @@ #include #include #include -#include +#include namespace py = pybind11; diff --git a/moveit_py/src/moveit/moveit_core/robot_model/robot_model.cpp b/moveit_py/src/moveit/moveit_core/robot_model/robot_model.cpp index 314cc06b06..a1da21f4be 100644 --- a/moveit_py/src/moveit/moveit_core/robot_model/robot_model.cpp +++ b/moveit_py/src/moveit/moveit_core/robot_model/robot_model.cpp @@ -34,12 +34,12 @@ /* Author: Peter David Fagan */ -#include "robot_model.h" +#include "robot_model.hpp" #include #include #include #include -#include +#include namespace moveit_py { diff --git a/moveit_py/src/moveit/moveit_core/robot_state/robot_state.cpp b/moveit_py/src/moveit/moveit_core/robot_state/robot_state.cpp index ed97ef08b6..e0d6016c68 100644 --- a/moveit_py/src/moveit/moveit_core/robot_state/robot_state.cpp +++ b/moveit_py/src/moveit/moveit_core/robot_state/robot_state.cpp @@ -34,11 +34,11 @@ /* Author: Peter David Fagan */ -#include "robot_state.h" +#include "robot_state.hpp" #include -#include +#include #include -#include +#include namespace moveit_py { diff --git a/moveit_py/src/moveit/moveit_core/robot_state/robot_state.h b/moveit_py/src/moveit/moveit_core/robot_state/robot_state.h index 7ac1497b29..d0223b1126 100644 --- a/moveit_py/src/moveit/moveit_core/robot_state/robot_state.h +++ b/moveit_py/src/moveit/moveit_core/robot_state/robot_state.h @@ -44,9 +44,9 @@ #endif #include #pragma GCC diagnostic pop -#include +#include #include -#include +#include namespace py = pybind11; diff --git a/moveit_py/src/moveit/moveit_core/robot_trajectory/robot_trajectory.cpp b/moveit_py/src/moveit/moveit_core/robot_trajectory/robot_trajectory.cpp index a18c121c96..b5360cbdc4 100644 --- a/moveit_py/src/moveit/moveit_core/robot_trajectory/robot_trajectory.cpp +++ b/moveit_py/src/moveit/moveit_core/robot_trajectory/robot_trajectory.cpp @@ -34,9 +34,9 @@ /* Author: Peter David Fagan */ -#include "robot_trajectory.h" -#include -#include +#include "robot_trajectory.hpp" +#include +#include namespace moveit_py { diff --git a/moveit_py/src/moveit/moveit_core/robot_trajectory/robot_trajectory.h b/moveit_py/src/moveit/moveit_core/robot_trajectory/robot_trajectory.h index 7e1cca5ace..293d346614 100644 --- a/moveit_py/src/moveit/moveit_core/robot_trajectory/robot_trajectory.h +++ b/moveit_py/src/moveit/moveit_core/robot_trajectory/robot_trajectory.h @@ -39,7 +39,7 @@ #include #include #include -#include +#include #include #include diff --git a/moveit_py/src/moveit/moveit_core/transforms/transforms.cpp b/moveit_py/src/moveit/moveit_core/transforms/transforms.cpp index fc79cdb5bc..5ea7a5ce00 100644 --- a/moveit_py/src/moveit/moveit_core/transforms/transforms.cpp +++ b/moveit_py/src/moveit/moveit_core/transforms/transforms.cpp @@ -34,7 +34,7 @@ /* Author: Peter David Fagan */ -#include "transforms.h" +#include "transforms.hpp" namespace moveit_py { diff --git a/moveit_py/src/moveit/moveit_core/transforms/transforms.h b/moveit_py/src/moveit/moveit_core/transforms/transforms.h index c8a72ccdb9..55aff743df 100644 --- a/moveit_py/src/moveit/moveit_core/transforms/transforms.h +++ b/moveit_py/src/moveit/moveit_core/transforms/transforms.h @@ -39,7 +39,7 @@ #include #include #include -#include +#include namespace py = pybind11; diff --git a/moveit_py/src/moveit/moveit_py_utils/src/copy_ros_msg.cpp b/moveit_py/src/moveit/moveit_py_utils/src/copy_ros_msg.cpp index 407a979493..b596ac889c 100644 --- a/moveit_py/src/moveit/moveit_py_utils/src/copy_ros_msg.cpp +++ b/moveit_py/src/moveit/moveit_py_utils/src/copy_ros_msg.cpp @@ -35,7 +35,7 @@ /* Author: Peter David Fagan */ #include -#include +#include namespace moveit_py { diff --git a/moveit_py/src/moveit/moveit_py_utils/src/ros_msg_typecasters.cpp b/moveit_py/src/moveit/moveit_py_utils/src/ros_msg_typecasters.cpp index 138d4f600a..6215ca3dda 100644 --- a/moveit_py/src/moveit/moveit_py_utils/src/ros_msg_typecasters.cpp +++ b/moveit_py/src/moveit/moveit_py_utils/src/ros_msg_typecasters.cpp @@ -34,7 +34,7 @@ /* Author: Peter David Fagan, Robert Haschke */ -#include +#include namespace py = pybind11; namespace moveit_py diff --git a/moveit_py/src/moveit/moveit_ros/moveit_cpp/moveit_cpp.h b/moveit_py/src/moveit/moveit_ros/moveit_cpp/moveit_cpp.h index 6c287ebe39..6dd6d55ad5 100644 --- a/moveit_py/src/moveit/moveit_ros/moveit_cpp/moveit_cpp.h +++ b/moveit_py/src/moveit/moveit_ros/moveit_cpp/moveit_cpp.h @@ -40,14 +40,14 @@ #include #include #include -#include +#include #include -#include -#include -#include +#include +#include +#include #include -#include "planning_component.h" +#include "planning_component.hpp" namespace py = pybind11; diff --git a/moveit_py/src/moveit/moveit_ros/moveit_cpp/planning_component.cpp b/moveit_py/src/moveit/moveit_ros/moveit_cpp/planning_component.cpp index e57083e553..0053e1129d 100644 --- a/moveit_py/src/moveit/moveit_ros/moveit_cpp/planning_component.cpp +++ b/moveit_py/src/moveit/moveit_ros/moveit_cpp/planning_component.cpp @@ -34,7 +34,7 @@ /* Author: Peter David Fagan */ -#include "planning_component.h" +#include "planning_component.hpp" #include namespace moveit_py diff --git a/moveit_py/src/moveit/moveit_ros/moveit_cpp/planning_component.h b/moveit_py/src/moveit/moveit_ros/moveit_cpp/planning_component.h index f0a7c04cee..69204b818c 100644 --- a/moveit_py/src/moveit/moveit_ros/moveit_cpp/planning_component.h +++ b/moveit_py/src/moveit/moveit_ros/moveit_cpp/planning_component.h @@ -41,16 +41,16 @@ #include #include #include -#include -#include -#include -#include +#include +#include +#include +#include #include #include -#include "moveit_cpp.h" -#include "../planning_scene_monitor/planning_scene_monitor.h" -#include "../../moveit_core/planning_interface/planning_response.h" +#include "moveit_cpp.hpp" +#include "../planning_scene_monitor/planning_scene_monitor.hpp" +#include "../../moveit_core/planning_interface/planning_response.hpp" namespace py = pybind11; diff --git a/moveit_py/src/moveit/moveit_ros/planning_scene_monitor/planning_scene_monitor.cpp b/moveit_py/src/moveit/moveit_ros/planning_scene_monitor/planning_scene_monitor.cpp index 1df36f6a0c..53a2730013 100644 --- a/moveit_py/src/moveit/moveit_ros/planning_scene_monitor/planning_scene_monitor.cpp +++ b/moveit_py/src/moveit/moveit_ros/planning_scene_monitor/planning_scene_monitor.cpp @@ -34,7 +34,7 @@ /* Author: Peter David Fagan */ -#include "planning_scene_monitor.h" +#include "planning_scene_monitor.hpp" namespace moveit_py { diff --git a/moveit_py/src/moveit/moveit_ros/planning_scene_monitor/planning_scene_monitor.h b/moveit_py/src/moveit/moveit_ros/planning_scene_monitor/planning_scene_monitor.h index c7c5713d9a..57b3e492a2 100644 --- a/moveit_py/src/moveit/moveit_ros/planning_scene_monitor/planning_scene_monitor.h +++ b/moveit_py/src/moveit/moveit_ros/planning_scene_monitor/planning_scene_monitor.h @@ -38,12 +38,12 @@ #include #include -#include -#include +#include +#include #include #include #include -#include +#include namespace py = pybind11; diff --git a/moveit_py/src/moveit/moveit_ros/trajectory_execution_manager/trajectory_execution_manager.cpp b/moveit_py/src/moveit/moveit_ros/trajectory_execution_manager/trajectory_execution_manager.cpp index 3872d17665..1c0693e638 100644 --- a/moveit_py/src/moveit/moveit_ros/trajectory_execution_manager/trajectory_execution_manager.cpp +++ b/moveit_py/src/moveit/moveit_ros/trajectory_execution_manager/trajectory_execution_manager.cpp @@ -34,7 +34,7 @@ /* Author: Matthijs van der Burgh */ -#include "trajectory_execution_manager.h" +#include "trajectory_execution_manager.hpp" namespace moveit_py { diff --git a/moveit_py/src/moveit/moveit_ros/trajectory_execution_manager/trajectory_execution_manager.h b/moveit_py/src/moveit/moveit_ros/trajectory_execution_manager/trajectory_execution_manager.h index 692f6f71ac..11f1ff159e 100644 --- a/moveit_py/src/moveit/moveit_ros/trajectory_execution_manager/trajectory_execution_manager.h +++ b/moveit_py/src/moveit/moveit_ros/trajectory_execution_manager/trajectory_execution_manager.h @@ -38,10 +38,10 @@ #include #include -#include -#include +#include +#include #include -#include +#include namespace py = pybind11; diff --git a/moveit_py/src/moveit/planning.cpp b/moveit_py/src/moveit/planning.cpp index 5e99f70815..5b1f83b339 100644 --- a/moveit_py/src/moveit/planning.cpp +++ b/moveit_py/src/moveit/planning.cpp @@ -34,10 +34,10 @@ /* Author: Peter David Fagan */ -#include "moveit_ros/moveit_cpp/moveit_cpp.h" -#include "moveit_ros/moveit_cpp/planning_component.h" -#include "moveit_ros/planning_scene_monitor/planning_scene_monitor.h" -#include "moveit_ros/trajectory_execution_manager/trajectory_execution_manager.h" +#include "moveit_ros/moveit_cpp/moveit_cpp.hpp" +#include "moveit_ros/moveit_cpp/planning_component.hpp" +#include "moveit_ros/planning_scene_monitor/planning_scene_monitor.hpp" +#include "moveit_ros/trajectory_execution_manager/trajectory_execution_manager.hpp" PYBIND11_MODULE(planning, m) { diff --git a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h index 6a0be17731..213fc629a3 100644 --- a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h +++ b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h @@ -36,17 +36,17 @@ #pragma once -#include +#include -#include +#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include #include #include diff --git a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp index 252d2a98d6..ed34b63fbc 100644 --- a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp +++ b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp @@ -34,12 +34,12 @@ /* Author: Ryan Luna */ -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include #include #include diff --git a/moveit_ros/benchmarks/src/BenchmarkOptions.cpp b/moveit_ros/benchmarks/src/BenchmarkOptions.cpp index c27f3c9cc1..3a788d8919 100644 --- a/moveit_ros/benchmarks/src/BenchmarkOptions.cpp +++ b/moveit_ros/benchmarks/src/BenchmarkOptions.cpp @@ -34,7 +34,7 @@ /* Author: Ryan Luna */ -#include +#include #include using moveit::getLogger; diff --git a/moveit_ros/benchmarks/src/RunBenchmark.cpp b/moveit_ros/benchmarks/src/RunBenchmark.cpp index e1a86af6d1..88eab1680d 100644 --- a/moveit_ros/benchmarks/src/RunBenchmark.cpp +++ b/moveit_ros/benchmarks/src/RunBenchmark.cpp @@ -36,8 +36,8 @@ #include -#include -#include +#include +#include #include #include #include diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h index 7573e83166..586ea6122e 100644 --- a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h +++ b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h @@ -43,7 +43,7 @@ #include -#include +#include #include #include diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h index 7cfcafa96a..8adce4d776 100644 --- a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h +++ b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h @@ -42,7 +42,7 @@ #include #include -#include +#include #include #include diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_component/src/global_planner_component.cpp b/moveit_ros/hybrid_planning/global_planner/global_planner_component/src/global_planner_component.cpp index 33b86f8325..d52c2e1713 100644 --- a/moveit_ros/hybrid_planning/global_planner/global_planner_component/src/global_planner_component.cpp +++ b/moveit_ros/hybrid_planning/global_planner/global_planner_component/src/global_planner_component.cpp @@ -32,9 +32,9 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include -#include -#include +#include +#include +#include #include #include diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h b/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h index a50afbef64..b9eb54400a 100644 --- a/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h +++ b/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h @@ -38,11 +38,11 @@ #pragma once #include -#include +#include // MoveitCpp -#include -#include +#include +#include namespace moveit::hybrid_planning { diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/src/moveit_planning_pipeline.cpp b/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/src/moveit_planning_pipeline.cpp index d93bfde272..6e8a3411c2 100644 --- a/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/src/moveit_planning_pipeline.cpp +++ b/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/src/moveit_planning_pipeline.cpp @@ -32,9 +32,9 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include -#include -#include +#include +#include +#include namespace moveit::hybrid_planning { diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h index 9944622202..0418959757 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h @@ -45,7 +45,7 @@ #include #include -#include +#include #include diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h index 4b10cea752..f2710c74cf 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h @@ -40,8 +40,8 @@ #include #include -#include -#include +#include +#include namespace moveit::hybrid_planning { diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/src/hybrid_planning_manager.cpp b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/src/hybrid_planning_manager.cpp index b069b9a19c..ec1e3a2f95 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/src/hybrid_planning_manager.cpp +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/src/hybrid_planning_manager.cpp @@ -32,8 +32,8 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include -#include +#include +#include #include #include diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h index 7fd25903a8..7c70fbc9f5 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h @@ -38,7 +38,7 @@ invalidated global trajectory. */ -#include +#include namespace moveit::hybrid_planning { diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h index 3378db79f0..795a4543cb 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h @@ -37,8 +37,8 @@ with the local planner. */ -#include -#include +#include +#include namespace moveit::hybrid_planning { diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/src/replan_invalidated_trajectory.cpp b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/src/replan_invalidated_trajectory.cpp index 6af466bc1a..ab7d616b43 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/src/replan_invalidated_trajectory.cpp +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/src/replan_invalidated_trajectory.cpp @@ -32,8 +32,8 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include -#include +#include +#include namespace moveit::hybrid_planning { diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/src/single_plan_execution.cpp b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/src/single_plan_execution.cpp index 5b1170ad24..4de4375f02 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/src/single_plan_execution.cpp +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/src/single_plan_execution.cpp @@ -32,7 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include namespace moveit::hybrid_planning { diff --git a/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h b/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h index d63ddda28a..d72c363f5e 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h +++ b/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h @@ -41,7 +41,7 @@ #pragma once #include -#include +#include namespace moveit::hybrid_planning { diff --git a/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/src/forward_trajectory.cpp b/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/src/forward_trajectory.cpp index 13086091bc..825129a0d8 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/src/forward_trajectory.cpp +++ b/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/src/forward_trajectory.cpp @@ -32,10 +32,10 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include -#include -#include -#include +#include +#include +#include +#include namespace { diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h index c3390be622..31b8354eff 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h @@ -41,8 +41,8 @@ #include #include -#include -#include +#include +#include #include #include diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h index 1ce83d7efc..164cd231a7 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h @@ -53,10 +53,10 @@ #include -#include -#include -#include -#include +#include +#include +#include +#include #include #include diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h index 7c3fc6b124..40f5ccf6e0 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h @@ -46,8 +46,8 @@ #include -#include -#include +#include +#include namespace moveit::hybrid_planning { diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/src/local_planner_component.cpp b/moveit_ros/hybrid_planning/local_planner/local_planner_component/src/local_planner_component.cpp index ab4bb28c66..f9914f2ee9 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/src/local_planner_component.cpp +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/src/local_planner_component.cpp @@ -32,13 +32,13 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include #include -#include -#include +#include +#include -#include +#include #include diff --git a/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h b/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h index ed73e0221d..16a1cd440e 100644 --- a/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h +++ b/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h @@ -38,8 +38,8 @@ is updated to the next global trajectory waypoint. Global trajectory updates simply replace the reference trajectory. */ -#include -#include +#include +#include namespace moveit::hybrid_planning { diff --git a/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/src/simple_sampler.cpp b/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/src/simple_sampler.cpp index ae3038ace1..c1ed50ab02 100644 --- a/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/src/simple_sampler.cpp +++ b/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/src/simple_sampler.cpp @@ -32,9 +32,9 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include -#include +#include namespace moveit::hybrid_planning { diff --git a/moveit_ros/hybrid_planning/test/test_basic_integration.cpp b/moveit_ros/hybrid_planning/test/test_basic_integration.cpp index 9a6beb355e..97399f272a 100644 --- a/moveit_ros/hybrid_planning/test/test_basic_integration.cpp +++ b/moveit_ros/hybrid_planning/test/test_basic_integration.cpp @@ -37,12 +37,12 @@ */ #include -#include -#include -#include +#include +#include +#include #include #include -#include +#include #include #include diff --git a/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h b/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h index c29d5ee858..642b71af83 100644 --- a/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h +++ b/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h @@ -36,11 +36,11 @@ #pragma once -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include namespace move_group { diff --git a/moveit_ros/move_group/include/moveit/move_group/move_group_context.h b/moveit_ros/move_group/include/moveit/move_group/move_group_context.h index acd57575d4..676ad3ec07 100644 --- a/moveit_ros/move_group/include/moveit/move_group/move_group_context.h +++ b/moveit_ros/move_group/include/moveit/move_group/move_group_context.h @@ -38,7 +38,7 @@ #include #include -#include +#include namespace moveit_cpp { diff --git a/moveit_ros/move_group/src/default_capabilities/apply_planning_scene_service_capability.cpp b/moveit_ros/move_group/src/default_capabilities/apply_planning_scene_service_capability.cpp index ec3725694e..2a26fed0ce 100644 --- a/moveit_ros/move_group/src/default_capabilities/apply_planning_scene_service_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/apply_planning_scene_service_capability.cpp @@ -34,9 +34,9 @@ /* Author: Michael Goerner */ -#include "apply_planning_scene_service_capability.h" -#include -#include +#include "apply_planning_scene_service_capability.hpp" +#include +#include #include namespace move_group diff --git a/moveit_ros/move_group/src/default_capabilities/apply_planning_scene_service_capability.h b/moveit_ros/move_group/src/default_capabilities/apply_planning_scene_service_capability.h index d48dbaa131..d220c88ae0 100644 --- a/moveit_ros/move_group/src/default_capabilities/apply_planning_scene_service_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/apply_planning_scene_service_capability.h @@ -36,7 +36,7 @@ #pragma once -#include +#include #include namespace move_group diff --git a/moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.cpp b/moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.cpp index 34af2a8094..0bf79bb987 100644 --- a/moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.cpp @@ -34,18 +34,18 @@ /* Author: Ioan Sucan */ -#include "cartesian_path_service_capability.h" -#include -#include -#include -#include +#include "cartesian_path_service_capability.hpp" +#include +#include +#include +#include #include -#include -#include -#include -#include +#include +#include +#include +#include #include -#include +#include #include using moveit::getLogger; diff --git a/moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.h b/moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.h index f0fe447cd7..9b2819009e 100644 --- a/moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.h @@ -36,7 +36,7 @@ #pragma once -#include +#include #include #include diff --git a/moveit_ros/move_group/src/default_capabilities/clear_octomap_service_capability.cpp b/moveit_ros/move_group/src/default_capabilities/clear_octomap_service_capability.cpp index a62b8b5ad5..376ab2a8ca 100644 --- a/moveit_ros/move_group/src/default_capabilities/clear_octomap_service_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/clear_octomap_service_capability.cpp @@ -34,9 +34,9 @@ /* Author: David Hershberger */ -#include "clear_octomap_service_capability.h" -#include -#include +#include "clear_octomap_service_capability.hpp" +#include +#include #include namespace diff --git a/moveit_ros/move_group/src/default_capabilities/clear_octomap_service_capability.h b/moveit_ros/move_group/src/default_capabilities/clear_octomap_service_capability.h index 05f0c3ff94..04a68f70da 100644 --- a/moveit_ros/move_group/src/default_capabilities/clear_octomap_service_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/clear_octomap_service_capability.h @@ -36,7 +36,7 @@ #pragma once -#include +#include #include namespace move_group diff --git a/moveit_ros/move_group/src/default_capabilities/execute_trajectory_action_capability.cpp b/moveit_ros/move_group/src/default_capabilities/execute_trajectory_action_capability.cpp index 8d78f2ac41..ff7959e439 100644 --- a/moveit_ros/move_group/src/default_capabilities/execute_trajectory_action_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/execute_trajectory_action_capability.cpp @@ -34,13 +34,13 @@ /* Author: Kentaro Wada */ -#include "execute_trajectory_action_capability.h" +#include "execute_trajectory_action_capability.hpp" -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include namespace move_group diff --git a/moveit_ros/move_group/src/default_capabilities/execute_trajectory_action_capability.h b/moveit_ros/move_group/src/default_capabilities/execute_trajectory_action_capability.h index ff4ebd36ea..174e041f16 100644 --- a/moveit_ros/move_group/src/default_capabilities/execute_trajectory_action_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/execute_trajectory_action_capability.h @@ -40,7 +40,7 @@ #pragma once -#include +#include #include #include diff --git a/moveit_ros/move_group/src/default_capabilities/get_group_urdf_capability.cpp b/moveit_ros/move_group/src/default_capabilities/get_group_urdf_capability.cpp index fffdbf52f9..7bb701fa2a 100644 --- a/moveit_ros/move_group/src/default_capabilities/get_group_urdf_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/get_group_urdf_capability.cpp @@ -34,10 +34,10 @@ /* Author: Sebastian Jahr */ -#include "get_group_urdf_capability.h" +#include "get_group_urdf_capability.hpp" -#include -#include +#include +#include #include #include diff --git a/moveit_ros/move_group/src/default_capabilities/get_group_urdf_capability.h b/moveit_ros/move_group/src/default_capabilities/get_group_urdf_capability.h index 05fb6b10ff..08cd2eeaa6 100644 --- a/moveit_ros/move_group/src/default_capabilities/get_group_urdf_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/get_group_urdf_capability.h @@ -37,7 +37,7 @@ #pragma once -#include +#include #include namespace move_group diff --git a/moveit_ros/move_group/src/default_capabilities/get_planning_scene_service_capability.cpp b/moveit_ros/move_group/src/default_capabilities/get_planning_scene_service_capability.cpp index 09aac4eed2..110914defe 100644 --- a/moveit_ros/move_group/src/default_capabilities/get_planning_scene_service_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/get_planning_scene_service_capability.cpp @@ -34,8 +34,8 @@ /* Author: Ioan Sucan */ -#include "get_planning_scene_service_capability.h" -#include +#include "get_planning_scene_service_capability.hpp" +#include namespace move_group { diff --git a/moveit_ros/move_group/src/default_capabilities/get_planning_scene_service_capability.h b/moveit_ros/move_group/src/default_capabilities/get_planning_scene_service_capability.h index 6b056296b4..a109de1e2a 100644 --- a/moveit_ros/move_group/src/default_capabilities/get_planning_scene_service_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/get_planning_scene_service_capability.h @@ -36,7 +36,7 @@ #pragma once -#include +#include #include namespace move_group diff --git a/moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.cpp b/moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.cpp index c2cd031305..2120ee1d20 100644 --- a/moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.cpp @@ -34,12 +34,12 @@ /* Author: Ioan Sucan */ -#include "kinematics_service_capability.h" -#include -#include -#include +#include "kinematics_service_capability.hpp" +#include +#include +#include #include -#include +#include #include namespace move_group diff --git a/moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.h b/moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.h index 0df58ea057..2d8118478a 100644 --- a/moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.h @@ -36,7 +36,7 @@ #pragma once -#include +#include #include #include diff --git a/moveit_ros/move_group/src/default_capabilities/load_geometry_from_file_service_capability.cpp b/moveit_ros/move_group/src/default_capabilities/load_geometry_from_file_service_capability.cpp index 93a7b51520..ba4b0bfedc 100644 --- a/moveit_ros/move_group/src/default_capabilities/load_geometry_from_file_service_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/load_geometry_from_file_service_capability.cpp @@ -34,10 +34,10 @@ /* Author: Bilal Gill */ -#include "load_geometry_from_file_service_capability.h" +#include "load_geometry_from_file_service_capability.hpp" -#include -#include +#include +#include #include #include diff --git a/moveit_ros/move_group/src/default_capabilities/load_geometry_from_file_service_capability.h b/moveit_ros/move_group/src/default_capabilities/load_geometry_from_file_service_capability.h index 095aba5465..15d366d1cb 100644 --- a/moveit_ros/move_group/src/default_capabilities/load_geometry_from_file_service_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/load_geometry_from_file_service_capability.h @@ -36,7 +36,7 @@ #pragma once -#include +#include #include namespace move_group diff --git a/moveit_ros/move_group/src/default_capabilities/move_action_capability.cpp b/moveit_ros/move_group/src/default_capabilities/move_action_capability.cpp index ba7e77bfae..bc00199f27 100644 --- a/moveit_ros/move_group/src/default_capabilities/move_action_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/move_action_capability.cpp @@ -34,15 +34,15 @@ /* Author: Ioan Sucan */ -#include "move_action_capability.h" - -#include -#include -#include -#include -#include -#include -#include +#include "move_action_capability.hpp" + +#include +#include +#include +#include +#include +#include +#include #include namespace move_group diff --git a/moveit_ros/move_group/src/default_capabilities/move_action_capability.h b/moveit_ros/move_group/src/default_capabilities/move_action_capability.h index cccae63f9c..4306130dfc 100644 --- a/moveit_ros/move_group/src/default_capabilities/move_action_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/move_action_capability.h @@ -36,7 +36,7 @@ #pragma once -#include +#include #include #include #include diff --git a/moveit_ros/move_group/src/default_capabilities/plan_service_capability.cpp b/moveit_ros/move_group/src/default_capabilities/plan_service_capability.cpp index 0a5018d2c3..b5450e4fac 100644 --- a/moveit_ros/move_group/src/default_capabilities/plan_service_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/plan_service_capability.cpp @@ -34,11 +34,11 @@ /* Author: Ioan Sucan */ -#include "plan_service_capability.h" +#include "plan_service_capability.hpp" -#include -#include -#include +#include +#include +#include #include namespace move_group diff --git a/moveit_ros/move_group/src/default_capabilities/plan_service_capability.h b/moveit_ros/move_group/src/default_capabilities/plan_service_capability.h index fc99b87e53..089cc20dab 100644 --- a/moveit_ros/move_group/src/default_capabilities/plan_service_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/plan_service_capability.h @@ -36,7 +36,7 @@ #pragma once -#include +#include #include namespace move_group diff --git a/moveit_ros/move_group/src/default_capabilities/query_planners_service_capability.cpp b/moveit_ros/move_group/src/default_capabilities/query_planners_service_capability.cpp index 9ea896bdc9..0bce586f3a 100644 --- a/moveit_ros/move_group/src/default_capabilities/query_planners_service_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/query_planners_service_capability.cpp @@ -34,10 +34,10 @@ /* Author: Ioan Sucan, Robert Haschke */ -#include "query_planners_service_capability.h" -#include -#include -#include +#include "query_planners_service_capability.hpp" +#include +#include +#include #include namespace move_group diff --git a/moveit_ros/move_group/src/default_capabilities/query_planners_service_capability.h b/moveit_ros/move_group/src/default_capabilities/query_planners_service_capability.h index 8fa02ea1ef..7842a20648 100644 --- a/moveit_ros/move_group/src/default_capabilities/query_planners_service_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/query_planners_service_capability.h @@ -36,7 +36,7 @@ #pragma once -#include +#include #include #include #include diff --git a/moveit_ros/move_group/src/default_capabilities/save_geometry_to_file_service_capability.cpp b/moveit_ros/move_group/src/default_capabilities/save_geometry_to_file_service_capability.cpp index 0053459bce..1c1ee225ea 100644 --- a/moveit_ros/move_group/src/default_capabilities/save_geometry_to_file_service_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/save_geometry_to_file_service_capability.cpp @@ -34,10 +34,10 @@ /* Author: Bilal Gill */ -#include "save_geometry_to_file_service_capability.h" +#include "save_geometry_to_file_service_capability.hpp" -#include -#include +#include +#include #include #include diff --git a/moveit_ros/move_group/src/default_capabilities/save_geometry_to_file_service_capability.h b/moveit_ros/move_group/src/default_capabilities/save_geometry_to_file_service_capability.h index 30fa21c75b..5ef3ecc4ab 100644 --- a/moveit_ros/move_group/src/default_capabilities/save_geometry_to_file_service_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/save_geometry_to_file_service_capability.h @@ -36,7 +36,7 @@ #pragma once -#include +#include #include namespace move_group diff --git a/moveit_ros/move_group/src/default_capabilities/state_validation_service_capability.cpp b/moveit_ros/move_group/src/default_capabilities/state_validation_service_capability.cpp index 0e48096cb9..295bc4af5a 100644 --- a/moveit_ros/move_group/src/default_capabilities/state_validation_service_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/state_validation_service_capability.cpp @@ -34,12 +34,12 @@ /* Author: Ioan Sucan */ -#include "state_validation_service_capability.h" -#include -#include -#include -#include -#include +#include "state_validation_service_capability.hpp" +#include +#include +#include +#include +#include namespace move_group { diff --git a/moveit_ros/move_group/src/default_capabilities/state_validation_service_capability.h b/moveit_ros/move_group/src/default_capabilities/state_validation_service_capability.h index 1efaf8caa9..2daf30eb11 100644 --- a/moveit_ros/move_group/src/default_capabilities/state_validation_service_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/state_validation_service_capability.h @@ -36,7 +36,7 @@ #pragma once -#include +#include #include namespace move_group diff --git a/moveit_ros/move_group/src/default_capabilities/tf_publisher_capability.cpp b/moveit_ros/move_group/src/default_capabilities/tf_publisher_capability.cpp index 8ed2af48c1..4f6f378a05 100644 --- a/moveit_ros/move_group/src/default_capabilities/tf_publisher_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/tf_publisher_capability.cpp @@ -34,14 +34,14 @@ /* Author: Jonas Tietz */ -#include "tf_publisher_capability.h" -#include -#include -#include -#include +#include "tf_publisher_capability.hpp" +#include +#include +#include +#include #include -#include -#include +#include +#include #include namespace move_group diff --git a/moveit_ros/move_group/src/default_capabilities/tf_publisher_capability.h b/moveit_ros/move_group/src/default_capabilities/tf_publisher_capability.h index 7c01174408..97643b6c92 100644 --- a/moveit_ros/move_group/src/default_capabilities/tf_publisher_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/tf_publisher_capability.h @@ -36,7 +36,7 @@ #pragma once -#include +#include #include namespace move_group diff --git a/moveit_ros/move_group/src/list_capabilities.cpp b/moveit_ros/move_group/src/list_capabilities.cpp index 78ff926dd5..01ba7e6082 100644 --- a/moveit_ros/move_group/src/list_capabilities.cpp +++ b/moveit_ros/move_group/src/list_capabilities.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include +#include #include #include diff --git a/moveit_ros/move_group/src/move_group.cpp b/moveit_ros/move_group/src/move_group.cpp index bb9629d191..2389100756 100644 --- a/moveit_ros/move_group/src/move_group.cpp +++ b/moveit_ros/move_group/src/move_group.cpp @@ -34,14 +34,14 @@ /* Author: Ioan Sucan */ -#include -#include +#include +#include #include -#include -#include +#include +#include #include -#include -#include +#include +#include #include #include #include diff --git a/moveit_ros/move_group/src/move_group_capability.cpp b/moveit_ros/move_group/src/move_group_capability.cpp index 3a33da9393..f0f6f70b85 100644 --- a/moveit_ros/move_group/src/move_group_capability.cpp +++ b/moveit_ros/move_group/src/move_group_capability.cpp @@ -34,10 +34,10 @@ /* Author: Ioan Sucan */ -#include -#include -#include -#include +#include +#include +#include +#include #include #include diff --git a/moveit_ros/move_group/src/move_group_context.cpp b/moveit_ros/move_group/src/move_group_context.cpp index 2d11ab6563..b0d4d2ed41 100644 --- a/moveit_ros/move_group/src/move_group_context.cpp +++ b/moveit_ros/move_group/src/move_group_context.cpp @@ -34,11 +34,11 @@ /* Author: Ioan Sucan */ -#include +#include -#include -#include -#include +#include +#include +#include #include namespace move_group diff --git a/moveit_ros/moveit_servo/demos/cpp_interface/demo_pose.cpp b/moveit_ros/moveit_servo/demos/cpp_interface/demo_pose.cpp index 4c713fd8b6..24e9bc33a3 100644 --- a/moveit_ros/moveit_servo/demos/cpp_interface/demo_pose.cpp +++ b/moveit_ros/moveit_servo/demos/cpp_interface/demo_pose.cpp @@ -45,7 +45,7 @@ #include #include #include -#include +#include #include using namespace moveit_servo; diff --git a/moveit_ros/moveit_servo/demos/cpp_interface/demo_twist.cpp b/moveit_ros/moveit_servo/demos/cpp_interface/demo_twist.cpp index 8c92fa4cfc..a73f319b3c 100644 --- a/moveit_ros/moveit_servo/demos/cpp_interface/demo_twist.cpp +++ b/moveit_ros/moveit_servo/demos/cpp_interface/demo_twist.cpp @@ -44,7 +44,7 @@ #include #include #include -#include +#include #include using namespace moveit_servo; diff --git a/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.hpp b/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.hpp index a68260bd8d..9752e5feb6 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.hpp +++ b/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.hpp @@ -42,8 +42,8 @@ #pragma once #include -#include -#include +#include +#include namespace moveit_servo { diff --git a/moveit_ros/moveit_servo/include/moveit_servo/servo.hpp b/moveit_ros/moveit_servo/include/moveit_servo/servo.hpp index d946bdc833..d4ec69e84a 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/servo.hpp +++ b/moveit_ros/moveit_servo/include/moveit_servo/servo.hpp @@ -45,13 +45,13 @@ #include #include #include -#include -#include -#include +#include +#include +#include #include #include #include -#include +#include #include #include #include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/utils/command.hpp b/moveit_ros/moveit_servo/include/moveit_servo/utils/command.hpp index 0e7f07d914..bf9c432527 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/utils/command.hpp +++ b/moveit_ros/moveit_servo/include/moveit_servo/utils/command.hpp @@ -42,8 +42,8 @@ #pragma once #include -#include -#include +#include +#include #include #include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/utils/common.hpp b/moveit_ros/moveit_servo/include/moveit_servo/utils/common.hpp index 060a113f56..6d44c18298 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/utils/common.hpp +++ b/moveit_ros/moveit_servo/include/moveit_servo/utils/common.hpp @@ -43,9 +43,9 @@ #include #include -#include -#include -#include +#include +#include +#include #include #include #include diff --git a/moveit_ros/moveit_servo/tests/test_utils.cpp b/moveit_ros/moveit_servo/tests/test_utils.cpp index d84fc503bd..6173c4fa3d 100644 --- a/moveit_ros/moveit_servo/tests/test_utils.cpp +++ b/moveit_ros/moveit_servo/tests/test_utils.cpp @@ -43,7 +43,7 @@ #include #include #include -#include +#include #include namespace diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h index 8b34da6d8a..7f58505143 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include #include #include diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.hpp b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.hpp index d73e7c43a7..aacfc8e03e 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.hpp +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.hpp @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include #include #include diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h index 429000b63a..fa29cd1ace 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include #include #include diff --git a/moveit_ros/occupancy_map_monitor/src/occupancy_map_monitor.cpp b/moveit_ros/occupancy_map_monitor/src/occupancy_map_monitor.cpp index abe0819917..e8943aa02b 100644 --- a/moveit_ros/occupancy_map_monitor/src/occupancy_map_monitor.cpp +++ b/moveit_ros/occupancy_map_monitor/src/occupancy_map_monitor.cpp @@ -34,8 +34,8 @@ /* Author: Ioan Sucan, Jon Binney */ -#include -#include +#include +#include #include #include #include diff --git a/moveit_ros/occupancy_map_monitor/src/occupancy_map_monitor_middleware_handle.cpp b/moveit_ros/occupancy_map_monitor/src/occupancy_map_monitor_middleware_handle.cpp index dd2eec7f22..4e870ca9f8 100644 --- a/moveit_ros/occupancy_map_monitor/src/occupancy_map_monitor_middleware_handle.cpp +++ b/moveit_ros/occupancy_map_monitor/src/occupancy_map_monitor_middleware_handle.cpp @@ -35,7 +35,7 @@ /* Author: Tyler Weaver */ #include -#include +#include #include #include diff --git a/moveit_ros/occupancy_map_monitor/src/occupancy_map_server.cpp b/moveit_ros/occupancy_map_monitor/src/occupancy_map_server.cpp index 1d09c9d604..7cd0dbb9bc 100644 --- a/moveit_ros/occupancy_map_monitor/src/occupancy_map_server.cpp +++ b/moveit_ros/occupancy_map_monitor/src/occupancy_map_server.cpp @@ -34,7 +34,7 @@ /* Author: Jon Binney, Ioan Sucan */ -#include +#include #include #include diff --git a/moveit_ros/occupancy_map_monitor/src/occupancy_map_updater.cpp b/moveit_ros/occupancy_map_monitor/src/occupancy_map_updater.cpp index 95d98a2ae3..7520e9fccd 100644 --- a/moveit_ros/occupancy_map_monitor/src/occupancy_map_updater.cpp +++ b/moveit_ros/occupancy_map_monitor/src/occupancy_map_updater.cpp @@ -34,8 +34,8 @@ /* Author: Ioan Sucan, Jon Binney */ -#include -#include +#include +#include #include #include #include diff --git a/moveit_ros/occupancy_map_monitor/test/occupancy_map_monitor_tests.cpp b/moveit_ros/occupancy_map_monitor/test/occupancy_map_monitor_tests.cpp index 46a6653ea5..207480e531 100644 --- a/moveit_ros/occupancy_map_monitor/test/occupancy_map_monitor_tests.cpp +++ b/moveit_ros/occupancy_map_monitor/test/occupancy_map_monitor_tests.cpp @@ -34,7 +34,7 @@ /* Author: Tyler Weaver */ -#include +#include #include #include diff --git a/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h b/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h index d54b7f475a..13d22bcfc9 100644 --- a/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h +++ b/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h @@ -38,10 +38,10 @@ #include #include -#include -#include -#include -#include +#include +#include +#include +#include #include #include diff --git a/moveit_ros/perception/depth_image_octomap_updater/src/depth_image_octomap_updater.cpp b/moveit_ros/perception/depth_image_octomap_updater/src/depth_image_octomap_updater.cpp index b9cd185d67..6912877fad 100644 --- a/moveit_ros/perception/depth_image_octomap_updater/src/depth_image_octomap_updater.cpp +++ b/moveit_ros/perception/depth_image_octomap_updater/src/depth_image_octomap_updater.cpp @@ -34,8 +34,8 @@ /* Author: Ioan Sucan, Suat Gedikli */ -#include -#include +#include +#include #include #include #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h index c2bddecc84..8cfe5bdeb8 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h @@ -36,7 +36,7 @@ #pragma once -#include +#include namespace mesh_filter { diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h index 64b8dadfca..def2a56f86 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h @@ -36,7 +36,7 @@ #pragma once -#include +#include #include #ifdef __APPLE__ #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h index 607fb663c0..d28b989435 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h @@ -36,7 +36,7 @@ #pragma once -#include +#include #include // for Vector3f namespace mesh_filter diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h index 9db4d91bc7..b1d4603657 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h @@ -37,9 +37,9 @@ #pragma once #include -#include -#include -#include +#include +#include +#include #include namespace tf2_ros diff --git a/moveit_ros/perception/mesh_filter/src/depth_self_filter_nodelet.cpp b/moveit_ros/perception/mesh_filter/src/depth_self_filter_nodelet.cpp index 266d8948ab..6de4cd1fdb 100644 --- a/moveit_ros/perception/mesh_filter/src/depth_self_filter_nodelet.cpp +++ b/moveit_ros/perception/mesh_filter/src/depth_self_filter_nodelet.cpp @@ -34,14 +34,14 @@ /* Author: Suat Gedikli */ -#include -#include -#include +#include +#include +#include #include #include #include -#include -#include +#include +#include #include namespace enc = sensor_msgs::image_encodings; diff --git a/moveit_ros/perception/mesh_filter/src/gl_mesh.cpp b/moveit_ros/perception/mesh_filter/src/gl_mesh.cpp index 00fba30bb3..96737abbdd 100644 --- a/moveit_ros/perception/mesh_filter/src/gl_mesh.cpp +++ b/moveit_ros/perception/mesh_filter/src/gl_mesh.cpp @@ -34,7 +34,7 @@ /* Author: Suat Gedikli */ -#include +#include #include #include #include diff --git a/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp b/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp index 0dea00e55c..e528cb5b55 100644 --- a/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp +++ b/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp @@ -42,7 +42,7 @@ #include #endif #include -#include +#include #include #include #include diff --git a/moveit_ros/perception/mesh_filter/src/mesh_filter.cpp b/moveit_ros/perception/mesh_filter/src/mesh_filter.cpp index 007e9e8397..06ec291625 100644 --- a/moveit_ros/perception/mesh_filter/src/mesh_filter.cpp +++ b/moveit_ros/perception/mesh_filter/src/mesh_filter.cpp @@ -34,8 +34,8 @@ /* Author: Suat Gedikli */ -#include -#include +#include +#include #include #include #include diff --git a/moveit_ros/perception/mesh_filter/src/mesh_filter_base.cpp b/moveit_ros/perception/mesh_filter/src/mesh_filter_base.cpp index 6b4b551b9f..333a703192 100644 --- a/moveit_ros/perception/mesh_filter/src/mesh_filter_base.cpp +++ b/moveit_ros/perception/mesh_filter/src/mesh_filter_base.cpp @@ -34,9 +34,9 @@ /* Author: Suat Gedikli */ -#include -#include -#include +#include +#include +#include #include #include diff --git a/moveit_ros/perception/mesh_filter/src/sensor_model.cpp b/moveit_ros/perception/mesh_filter/src/sensor_model.cpp index 9ff5cdbf0c..a35edd3c1b 100644 --- a/moveit_ros/perception/mesh_filter/src/sensor_model.cpp +++ b/moveit_ros/perception/mesh_filter/src/sensor_model.cpp @@ -34,7 +34,7 @@ /* Author: Suat Gedikli */ -#include +#include #include mesh_filter::SensorModel::~SensorModel() = default; diff --git a/moveit_ros/perception/mesh_filter/src/stereo_camera_model.cpp b/moveit_ros/perception/mesh_filter/src/stereo_camera_model.cpp index eaa9d54118..3189986aa2 100644 --- a/moveit_ros/perception/mesh_filter/src/stereo_camera_model.cpp +++ b/moveit_ros/perception/mesh_filter/src/stereo_camera_model.cpp @@ -34,8 +34,8 @@ /* Author: Suat Gedikli */ -#include -#include +#include +#include mesh_filter::StereoCameraModel::Parameters::Parameters(unsigned width, unsigned height, float near_clipping_plane_distance, diff --git a/moveit_ros/perception/mesh_filter/test/mesh_filter_test.cpp b/moveit_ros/perception/mesh_filter/test/mesh_filter_test.cpp index 08c78ec3f2..abfe43a15d 100644 --- a/moveit_ros/perception/mesh_filter/test/mesh_filter_test.cpp +++ b/moveit_ros/perception/mesh_filter/test/mesh_filter_test.cpp @@ -33,8 +33,8 @@ *********************************************************************/ #include -#include -#include +#include +#include #include #include #include diff --git a/moveit_ros/perception/point_containment_filter/src/shape_mask.cpp b/moveit_ros/perception/point_containment_filter/src/shape_mask.cpp index db931d5b54..73a532fbe4 100644 --- a/moveit_ros/perception/point_containment_filter/src/shape_mask.cpp +++ b/moveit_ros/perception/point_containment_filter/src/shape_mask.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include +#include #include #include #include diff --git a/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h b/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h index 79b0c0c33e..e768005753 100644 --- a/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h +++ b/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h @@ -46,8 +46,8 @@ #include #endif #include -#include -#include +#include +#include #include diff --git a/moveit_ros/perception/pointcloud_octomap_updater/src/plugin_init.cpp b/moveit_ros/perception/pointcloud_octomap_updater/src/plugin_init.cpp index a586dbaae3..fc91e7d99e 100644 --- a/moveit_ros/perception/pointcloud_octomap_updater/src/plugin_init.cpp +++ b/moveit_ros/perception/pointcloud_octomap_updater/src/plugin_init.cpp @@ -35,6 +35,6 @@ /* Author: Ioan Sucan */ #include -#include +#include CLASS_LOADER_REGISTER_CLASS(occupancy_map_monitor::PointCloudOctomapUpdater, occupancy_map_monitor::OccupancyMapUpdater) diff --git a/moveit_ros/perception/pointcloud_octomap_updater/src/pointcloud_octomap_updater.cpp b/moveit_ros/perception/pointcloud_octomap_updater/src/pointcloud_octomap_updater.cpp index bce0275430..c652430513 100644 --- a/moveit_ros/perception/pointcloud_octomap_updater/src/pointcloud_octomap_updater.cpp +++ b/moveit_ros/perception/pointcloud_octomap_updater/src/pointcloud_octomap_updater.cpp @@ -35,8 +35,8 @@ /* Author: Jon Binney, Ioan Sucan */ #include -#include -#include +#include +#include #include #include #include diff --git a/moveit_ros/perception/semantic_world/src/semantic_world.cpp b/moveit_ros/perception/semantic_world/src/semantic_world.cpp index 337630c267..fb9b659b4d 100644 --- a/moveit_ros/perception/semantic_world/src/semantic_world.cpp +++ b/moveit_ros/perception/semantic_world/src/semantic_world.cpp @@ -37,7 +37,7 @@ #include #include // MoveIt -#include +#include #include #include #include diff --git a/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h b/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h index 93c67a8d5d..c4f3615961 100644 --- a/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h +++ b/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h @@ -35,7 +35,7 @@ #pragma once #include -#include +#include namespace collision_detection { diff --git a/moveit_ros/planning/collision_plugin_loader/src/collision_plugin_loader.cpp b/moveit_ros/planning/collision_plugin_loader/src/collision_plugin_loader.cpp index ea362c574b..e91b8e93a7 100644 --- a/moveit_ros/planning/collision_plugin_loader/src/collision_plugin_loader.cpp +++ b/moveit_ros/planning/collision_plugin_loader/src/collision_plugin_loader.cpp @@ -32,7 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include #include namespace collision_detection diff --git a/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h b/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h index 4aeeda5758..ced71f9eda 100644 --- a/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h +++ b/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include namespace constraint_sampler_manager_loader { diff --git a/moveit_ros/planning/constraint_sampler_manager_loader/src/constraint_sampler_manager_loader.cpp b/moveit_ros/planning/constraint_sampler_manager_loader/src/constraint_sampler_manager_loader.cpp index cd069ca821..074b397c02 100644 --- a/moveit_ros/planning/constraint_sampler_manager_loader/src/constraint_sampler_manager_loader.cpp +++ b/moveit_ros/planning/constraint_sampler_manager_loader/src/constraint_sampler_manager_loader.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include +#include #include #include #include diff --git a/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h b/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h index 96c645da15..e7494cf73c 100644 --- a/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h +++ b/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h @@ -36,9 +36,9 @@ #pragma once -#include -#include -#include +#include +#include +#include #include #include diff --git a/moveit_ros/planning/kinematics_plugin_loader/src/kinematics_plugin_loader.cpp b/moveit_ros/planning/kinematics_plugin_loader/src/kinematics_plugin_loader.cpp index db723955d5..ead7aa044a 100644 --- a/moveit_ros/planning/kinematics_plugin_loader/src/kinematics_plugin_loader.cpp +++ b/moveit_ros/planning/kinematics_plugin_loader/src/kinematics_plugin_loader.cpp @@ -34,8 +34,8 @@ /* Author: Ioan Sucan, Dave Coleman */ -#include -#include +#include +#include #include #include #include diff --git a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h index 15251ccdc9..eeaf4ab415 100644 --- a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h +++ b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h @@ -40,11 +40,11 @@ #pragma once #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include namespace moveit_cpp diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h index 5f2d9dd80b..e5bcddb190 100644 --- a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h +++ b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h @@ -36,11 +36,11 @@ #pragma once -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include #include diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h index 2248857584..e755e58c30 100644 --- a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h +++ b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include #include #include diff --git a/moveit_ros/planning/plan_execution/src/plan_execution.cpp b/moveit_ros/planning/plan_execution/src/plan_execution.cpp index 6e0452f410..b787ecedc2 100644 --- a/moveit_ros/planning/plan_execution/src/plan_execution.cpp +++ b/moveit_ros/planning/plan_execution/src/plan_execution.cpp @@ -34,12 +34,12 @@ /* Author: Ioan Sucan */ -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include #include #include #include @@ -50,7 +50,7 @@ #include // #include -// #include +// #include namespace plan_execution { diff --git a/moveit_ros/planning/planning_components_tools/src/display_random_state.cpp b/moveit_ros/planning/planning_components_tools/src/display_random_state.cpp index 0118986c5c..9f8993c613 100644 --- a/moveit_ros/planning/planning_components_tools/src/display_random_state.cpp +++ b/moveit_ros/planning/planning_components_tools/src/display_random_state.cpp @@ -35,7 +35,7 @@ /* Author: Ioan Sucan */ #include -#include +#include #include using namespace std::chrono_literals; diff --git a/moveit_ros/planning/planning_components_tools/src/evaluate_collision_checking_speed.cpp b/moveit_ros/planning/planning_components_tools/src/evaluate_collision_checking_speed.cpp index 93b8443fac..7c9d15eb55 100644 --- a/moveit_ros/planning/planning_components_tools/src/evaluate_collision_checking_speed.cpp +++ b/moveit_ros/planning/planning_components_tools/src/evaluate_collision_checking_speed.cpp @@ -35,7 +35,7 @@ /* Author: Ioan Sucan, Sachin Chitta */ #include -#include +#include #include #include #include diff --git a/moveit_ros/planning/planning_components_tools/src/print_planning_model_info.cpp b/moveit_ros/planning/planning_components_tools/src/print_planning_model_info.cpp index f868d5f622..01eed4e5d2 100644 --- a/moveit_ros/planning/planning_components_tools/src/print_planning_model_info.cpp +++ b/moveit_ros/planning/planning_components_tools/src/print_planning_model_info.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include +#include #include #include #include diff --git a/moveit_ros/planning/planning_components_tools/src/print_planning_scene_info.cpp b/moveit_ros/planning/planning_components_tools/src/print_planning_scene_info.cpp index e8a8a8ec79..72a5491fb6 100644 --- a/moveit_ros/planning/planning_components_tools/src/print_planning_scene_info.cpp +++ b/moveit_ros/planning/planning_components_tools/src/print_planning_scene_info.cpp @@ -37,7 +37,7 @@ */ // MoveIt -#include +#include #include #include #include diff --git a/moveit_ros/planning/planning_components_tools/src/publish_scene_from_text.cpp b/moveit_ros/planning/planning_components_tools/src/publish_scene_from_text.cpp index d083fa46f6..5f4d4194a2 100644 --- a/moveit_ros/planning/planning_components_tools/src/publish_scene_from_text.cpp +++ b/moveit_ros/planning/planning_components_tools/src/publish_scene_from_text.cpp @@ -35,7 +35,7 @@ /* Author: Ioan Sucan */ #include -#include +#include #include #include #include diff --git a/moveit_ros/planning/planning_components_tools/src/visualize_robot_collision_volume.cpp b/moveit_ros/planning/planning_components_tools/src/visualize_robot_collision_volume.cpp index 8b5f517535..05e451622f 100644 --- a/moveit_ros/planning/planning_components_tools/src/visualize_robot_collision_volume.cpp +++ b/moveit_ros/planning/planning_components_tools/src/visualize_robot_collision_volume.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include +#include #include #include #include diff --git a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h index 89115bbdb6..6ba0029d9c 100644 --- a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h +++ b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h @@ -41,14 +41,14 @@ #include -#include -#include -#include +#include +#include +#include #include #include #include #include -#include +#include #include namespace planning_pipeline diff --git a/moveit_ros/planning/planning_pipeline/src/planning_pipeline.cpp b/moveit_ros/planning/planning_pipeline/src/planning_pipeline.cpp index 882ab97b13..34f30375c8 100644 --- a/moveit_ros/planning/planning_pipeline/src/planning_pipeline.cpp +++ b/moveit_ros/planning/planning_pipeline/src/planning_pipeline.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan, Sebastian Jahr */ -#include +#include #include #include diff --git a/moveit_ros/planning/planning_pipeline/test/planning_pipeline_test_plugins.cpp b/moveit_ros/planning/planning_pipeline/test/planning_pipeline_test_plugins.cpp index 1b5d8986ac..4a715909b3 100644 --- a/moveit_ros/planning/planning_pipeline/test/planning_pipeline_test_plugins.cpp +++ b/moveit_ros/planning/planning_pipeline/test/planning_pipeline_test_plugins.cpp @@ -35,9 +35,9 @@ /* Author: Sebastian Jahr */ #include -#include -#include -#include +#include +#include +#include #include namespace planning_pipeline_test diff --git a/moveit_ros/planning/planning_pipeline/test/planning_pipeline_tests.cpp b/moveit_ros/planning/planning_pipeline/test/planning_pipeline_tests.cpp index 7100a69f09..50029d8770 100644 --- a/moveit_ros/planning/planning_pipeline/test/planning_pipeline_tests.cpp +++ b/moveit_ros/planning/planning_pipeline/test/planning_pipeline_tests.cpp @@ -36,8 +36,8 @@ #include -#include -#include +#include +#include namespace { diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.hpp b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.hpp index 779a7dd9d4..b1efd40c7a 100644 --- a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.hpp +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.hpp @@ -37,8 +37,8 @@ #pragma once -#include -#include +#include +#include namespace moveit { diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.hpp b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.hpp index 9c9760e2e4..23a62d0867 100644 --- a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.hpp +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.hpp @@ -38,10 +38,10 @@ #pragma once #include -#include -#include -#include -#include +#include +#include +#include +#include namespace moveit { diff --git a/moveit_ros/planning/planning_request_adapter_plugins/src/check_for_stacked_constraints.cpp b/moveit_ros/planning/planning_request_adapter_plugins/src/check_for_stacked_constraints.cpp index 6aed9555b2..e0b60847c1 100644 --- a/moveit_ros/planning/planning_request_adapter_plugins/src/check_for_stacked_constraints.cpp +++ b/moveit_ros/planning/planning_request_adapter_plugins/src/check_for_stacked_constraints.cpp @@ -37,7 +37,7 @@ * that is the case, a warning is created but the planning process is not interrupted. */ -#include +#include #include #include #include diff --git a/moveit_ros/planning/planning_request_adapter_plugins/src/check_start_state_bounds.cpp b/moveit_ros/planning/planning_request_adapter_plugins/src/check_start_state_bounds.cpp index bde29d5e12..315084ebef 100644 --- a/moveit_ros/planning/planning_request_adapter_plugins/src/check_start_state_bounds.cpp +++ b/moveit_ros/planning/planning_request_adapter_plugins/src/check_start_state_bounds.cpp @@ -43,9 +43,9 @@ * outside its limits for it to be “fixable”. */ -#include -#include -#include +#include +#include +#include #include #include #include diff --git a/moveit_ros/planning/planning_request_adapter_plugins/src/check_start_state_collision.cpp b/moveit_ros/planning/planning_request_adapter_plugins/src/check_start_state_collision.cpp index 3f3d22f6f2..99ccf820d7 100644 --- a/moveit_ros/planning/planning_request_adapter_plugins/src/check_start_state_collision.cpp +++ b/moveit_ros/planning/planning_request_adapter_plugins/src/check_start_state_collision.cpp @@ -36,9 +36,9 @@ * Desc: This adapter checks if the start state is in collision. */ -#include -#include -#include +#include +#include +#include #include #include #include diff --git a/moveit_ros/planning/planning_request_adapter_plugins/src/resolve_constraint_frames.cpp b/moveit_ros/planning/planning_request_adapter_plugins/src/resolve_constraint_frames.cpp index 55b0562b79..b6316b5ddb 100644 --- a/moveit_ros/planning/planning_request_adapter_plugins/src/resolve_constraint_frames.cpp +++ b/moveit_ros/planning/planning_request_adapter_plugins/src/resolve_constraint_frames.cpp @@ -38,8 +38,8 @@ attached object are not known to a planner. */ -#include -#include +#include +#include #include #include diff --git a/moveit_ros/planning/planning_request_adapter_plugins/src/validate_workspace_bounds.cpp b/moveit_ros/planning/planning_request_adapter_plugins/src/validate_workspace_bounds.cpp index de0510ef3a..a21dffe61e 100644 --- a/moveit_ros/planning/planning_request_adapter_plugins/src/validate_workspace_bounds.cpp +++ b/moveit_ros/planning/planning_request_adapter_plugins/src/validate_workspace_bounds.cpp @@ -37,7 +37,7 @@ * The default workspace is a cube whose edge length is defined with a ROS 2 parameter. */ -#include +#include #include #include #include diff --git a/moveit_ros/planning/planning_response_adapter_plugins/src/add_ruckig_traj_smoothing.cpp b/moveit_ros/planning/planning_response_adapter_plugins/src/add_ruckig_traj_smoothing.cpp index fd6a5b4204..5c566bd75b 100644 --- a/moveit_ros/planning/planning_response_adapter_plugins/src/add_ruckig_traj_smoothing.cpp +++ b/moveit_ros/planning/planning_response_adapter_plugins/src/add_ruckig_traj_smoothing.cpp @@ -38,8 +38,8 @@ */ #include -#include -#include +#include +#include #include #include diff --git a/moveit_ros/planning/planning_response_adapter_plugins/src/add_time_optimal_parameterization.cpp b/moveit_ros/planning/planning_response_adapter_plugins/src/add_time_optimal_parameterization.cpp index 7b8ed0b13c..b5097dce5f 100644 --- a/moveit_ros/planning/planning_response_adapter_plugins/src/add_time_optimal_parameterization.cpp +++ b/moveit_ros/planning/planning_response_adapter_plugins/src/add_time_optimal_parameterization.cpp @@ -34,8 +34,8 @@ /* Author: Ioan Sucan, Michael Ferguson */ -#include -#include +#include +#include #include #include diff --git a/moveit_ros/planning/planning_response_adapter_plugins/src/display_motion_path.cpp b/moveit_ros/planning/planning_response_adapter_plugins/src/display_motion_path.cpp index e5fcb1bc03..bc6fa5f605 100644 --- a/moveit_ros/planning/planning_response_adapter_plugins/src/display_motion_path.cpp +++ b/moveit_ros/planning/planning_response_adapter_plugins/src/display_motion_path.cpp @@ -36,8 +36,8 @@ Desc: Response adapter to display the motion path in RVIZ by publishing as EE pose marker array via ROS topic. */ -#include -#include +#include +#include #include #include #include diff --git a/moveit_ros/planning/planning_response_adapter_plugins/src/validate_path.cpp b/moveit_ros/planning/planning_response_adapter_plugins/src/validate_path.cpp index c5e47cda1f..1284ba821b 100644 --- a/moveit_ros/planning/planning_response_adapter_plugins/src/validate_path.cpp +++ b/moveit_ros/planning/planning_response_adapter_plugins/src/validate_path.cpp @@ -36,11 +36,11 @@ Desc: Response adapter that checks a path for validity (collision avoidance, feasibility and constraint satisfaction) */ -#include +#include #include #include #include -#include +#include #include namespace default_planning_response_adapters diff --git a/moveit_ros/planning/planning_scene_monitor/demos/demo_scene.cpp b/moveit_ros/planning/planning_scene_monitor/demos/demo_scene.cpp index 0e0c873de6..e3ed5af569 100644 --- a/moveit_ros/planning/planning_scene_monitor/demos/demo_scene.cpp +++ b/moveit_ros/planning/planning_scene_monitor/demos/demo_scene.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include +#include #include #include #include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h index b1ff502d9c..273d4b1049 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h @@ -50,7 +50,7 @@ #include -#include +#include namespace planning_scene_monitor { diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.hpp b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.hpp index c5f33cfc96..ee7a1d2a38 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.hpp +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.hpp @@ -42,7 +42,7 @@ #include #include -#include +#include namespace planning_scene_monitor { diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h index 54007cb85f..434c81a43e 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h @@ -39,12 +39,12 @@ #include #include #include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include #include #include #include @@ -52,7 +52,7 @@ #include #include -#include +#include namespace planning_scene_monitor { diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h index 9975093c06..08c7fadce9 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h @@ -36,10 +36,10 @@ #pragma once -#include -#include -#include -#include +#include +#include +#include +#include #include #include #include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.hpp b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.hpp index 4c2ec8fbe8..d691173065 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.hpp +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.hpp @@ -36,7 +36,7 @@ #pragma once -#include +#include #include namespace planning_scene_monitor diff --git a/moveit_ros/planning/planning_scene_monitor/src/current_state_monitor.cpp b/moveit_ros/planning/planning_scene_monitor/src/current_state_monitor.cpp index 572e2fd188..eca1c474b9 100644 --- a/moveit_ros/planning/planning_scene_monitor/src/current_state_monitor.cpp +++ b/moveit_ros/planning/planning_scene_monitor/src/current_state_monitor.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include +#include #include #include diff --git a/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp b/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp index 106a6fd663..478e98d1b9 100644 --- a/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp +++ b/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp @@ -34,10 +34,10 @@ /* Author: Ioan Sucan */ -#include -#include -#include -#include +#include +#include +#include +#include #include #include diff --git a/moveit_ros/planning/planning_scene_monitor/src/trajectory_monitor.cpp b/moveit_ros/planning/planning_scene_monitor/src/trajectory_monitor.cpp index 1fe9ca0f4a..5f8198fd11 100644 --- a/moveit_ros/planning/planning_scene_monitor/src/trajectory_monitor.cpp +++ b/moveit_ros/planning/planning_scene_monitor/src/trajectory_monitor.cpp @@ -34,9 +34,9 @@ /* Author: Ioan Sucan */ -#include +#include #include -#include +#include #include #include #include diff --git a/moveit_ros/planning/planning_scene_monitor/test/current_state_monitor_tests.cpp b/moveit_ros/planning/planning_scene_monitor/test/current_state_monitor_tests.cpp index 6e46e6538b..2977b0f76c 100644 --- a/moveit_ros/planning/planning_scene_monitor/test/current_state_monitor_tests.cpp +++ b/moveit_ros/planning/planning_scene_monitor/test/current_state_monitor_tests.cpp @@ -40,8 +40,8 @@ #include #include -#include -#include +#include +#include #include #include diff --git a/moveit_ros/planning/planning_scene_monitor/test/planning_scene_monitor_test.cpp b/moveit_ros/planning/planning_scene_monitor/test/planning_scene_monitor_test.cpp index 806a88f3ac..b04604ff5e 100644 --- a/moveit_ros/planning/planning_scene_monitor/test/planning_scene_monitor_test.cpp +++ b/moveit_ros/planning/planning_scene_monitor/test/planning_scene_monitor_test.cpp @@ -43,8 +43,8 @@ #include // Main class -#include -#include +#include +#include class PlanningSceneMonitorTest : public ::testing::Test { diff --git a/moveit_ros/planning/planning_scene_monitor/test/trajectory_monitor_tests.cpp b/moveit_ros/planning/planning_scene_monitor/test/trajectory_monitor_tests.cpp index 002f2b395a..0b957fdf43 100644 --- a/moveit_ros/planning/planning_scene_monitor/test/trajectory_monitor_tests.cpp +++ b/moveit_ros/planning/planning_scene_monitor/test/trajectory_monitor_tests.cpp @@ -40,9 +40,9 @@ #include #include #include -#include -#include -#include +#include +#include +#include #include #include diff --git a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h index 6445876478..788dced0d2 100644 --- a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h +++ b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include #if __has_include() #include #else diff --git a/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp b/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp index e96337a83e..de43e05744 100644 --- a/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp +++ b/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp @@ -35,7 +35,7 @@ /* Author: Ioan Sucan, Mathias Lüdtke, Dave Coleman */ // MoveIt -#include +#include #include #include #include diff --git a/moveit_ros/planning/rdf_loader/src/synchronized_string_parameter.cpp b/moveit_ros/planning/rdf_loader/src/synchronized_string_parameter.cpp index fa36d0b5ab..ac87024b98 100644 --- a/moveit_ros/planning/rdf_loader/src/synchronized_string_parameter.cpp +++ b/moveit_ros/planning/rdf_loader/src/synchronized_string_parameter.cpp @@ -34,7 +34,7 @@ /* Author: David V. Lu!! */ -#include +#include namespace rdf_loader { diff --git a/moveit_ros/planning/rdf_loader/test/test_rdf_integration.cpp b/moveit_ros/planning/rdf_loader/test/test_rdf_integration.cpp index 9d813402b5..d64e2ce70a 100644 --- a/moveit_ros/planning/rdf_loader/test/test_rdf_integration.cpp +++ b/moveit_ros/planning/rdf_loader/test/test_rdf_integration.cpp @@ -34,7 +34,7 @@ /* Author: David V. Lu!! */ -#include +#include #include #include diff --git a/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h b/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h index 8b7c54220d..6f65c2d02c 100644 --- a/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h +++ b/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h @@ -36,10 +36,10 @@ #pragma once -#include -#include -#include -#include +#include +#include +#include +#include namespace robot_model_loader { diff --git a/moveit_ros/planning/robot_model_loader/src/robot_model_loader.cpp b/moveit_ros/planning/robot_model_loader/src/robot_model_loader.cpp index 40a86a1483..5a6ea01291 100644 --- a/moveit_ros/planning/robot_model_loader/src/robot_model_loader.cpp +++ b/moveit_ros/planning/robot_model_loader/src/robot_model_loader.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan, E. Gil Jones */ -#include +#include #include #include #include diff --git a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h index 1bb055e20d..bcc394fc1a 100644 --- a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h +++ b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h @@ -36,21 +36,21 @@ #pragma once -#include -#include -#include +#include +#include +#include #include #include #include #include -#include +#include #include #include #include #include -#include +#include namespace trajectory_execution_manager { diff --git a/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp b/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp index 8a863ef80d..fd913c7960 100644 --- a/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp +++ b/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp @@ -34,9 +34,9 @@ /* Author: Ioan Sucan */ -#include -#include -#include +#include +#include +#include #include #include #include diff --git a/moveit_ros/planning/trajectory_execution_manager/test/test_execution_manager.cpp b/moveit_ros/planning/trajectory_execution_manager/test/test_execution_manager.cpp index f6a7683f2b..00963d0792 100644 --- a/moveit_ros/planning/trajectory_execution_manager/test/test_execution_manager.cpp +++ b/moveit_ros/planning/trajectory_execution_manager/test/test_execution_manager.cpp @@ -43,8 +43,8 @@ #include // Main class -#include -#include +#include +#include // Msgs #include diff --git a/moveit_ros/planning/trajectory_execution_manager/test/test_moveit_controller_manager.h b/moveit_ros/planning/trajectory_execution_manager/test/test_moveit_controller_manager.h index 319a97c7ff..7c92386e50 100644 --- a/moveit_ros/planning/trajectory_execution_manager/test/test_moveit_controller_manager.h +++ b/moveit_ros/planning/trajectory_execution_manager/test/test_moveit_controller_manager.h @@ -37,7 +37,7 @@ #pragma once #include -#include +#include #include #include diff --git a/moveit_ros/planning/trajectory_execution_manager/test/test_moveit_controller_manager_plugin.cpp b/moveit_ros/planning/trajectory_execution_manager/test/test_moveit_controller_manager_plugin.cpp index 6da8ab307d..a8bc5f9fea 100644 --- a/moveit_ros/planning/trajectory_execution_manager/test/test_moveit_controller_manager_plugin.cpp +++ b/moveit_ros/planning/trajectory_execution_manager/test/test_moveit_controller_manager_plugin.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include "test_moveit_controller_manager.h" +#include "test_moveit_controller_manager.hpp" #include PLUGINLIB_EXPORT_CLASS(test_moveit_controller_manager::TestRos2ControlManager, diff --git a/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h b/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h index 9911a9dd10..0295e3216b 100644 --- a/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h +++ b/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h @@ -38,8 +38,8 @@ #include #include -#include -#include +#include +#include namespace moveit { diff --git a/moveit_ros/planning_interface/common_planning_interface_objects/src/common_objects.cpp b/moveit_ros/planning_interface/common_planning_interface_objects/src/common_objects.cpp index 6f92f4115d..66b1fe08b4 100644 --- a/moveit_ros/planning_interface/common_planning_interface_objects/src/common_objects.cpp +++ b/moveit_ros/planning_interface/common_planning_interface_objects/src/common_objects.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include +#include using namespace planning_scene_monitor; using namespace robot_model_loader; diff --git a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h index 3c15fbafbe..bd6c4bb978 100644 --- a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h +++ b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h @@ -37,9 +37,9 @@ #pragma once -#include -#include -#include +#include +#include +#include #include #include #include @@ -58,7 +58,7 @@ #include #include -#include +#include namespace moveit { diff --git a/moveit_ros/planning_interface/planning_scene_interface/src/planning_scene_interface.cpp b/moveit_ros/planning_interface/planning_scene_interface/src/planning_scene_interface.cpp index a4277f0731..036e34dfd3 100644 --- a/moveit_ros/planning_interface/planning_scene_interface/src/planning_scene_interface.cpp +++ b/moveit_ros/planning_interface/planning_scene_interface/src/planning_scene_interface.cpp @@ -34,8 +34,8 @@ /* Author: Ioan Sucan, Sachin Chitta */ -#include -#include +#include +#include #include #include #include diff --git a/moveit_ros/planning_interface/test/move_group_interface_cpp_test.cpp b/moveit_ros/planning_interface/test/move_group_interface_cpp_test.cpp index 2b0595005e..13b98f75aa 100644 --- a/moveit_ros/planning_interface/test/move_group_interface_cpp_test.cpp +++ b/moveit_ros/planning_interface/test/move_group_interface_cpp_test.cpp @@ -52,10 +52,10 @@ #include // MoveIt -#include -#include -#include -#include +#include +#include +#include +#include // TF2 #include diff --git a/moveit_ros/planning_interface/test/move_group_ompl_constraints_test.cpp b/moveit_ros/planning_interface/test/move_group_ompl_constraints_test.cpp index c34992291d..8d72dee6de 100644 --- a/moveit_ros/planning_interface/test/move_group_ompl_constraints_test.cpp +++ b/moveit_ros/planning_interface/test/move_group_ompl_constraints_test.cpp @@ -45,9 +45,9 @@ #include // MoveIt -#include -#include -#include +#include +#include +#include #include // accuracy tested for position and orientation diff --git a/moveit_ros/trajectory_cache/src/trajectory_cache.cpp b/moveit_ros/trajectory_cache/src/trajectory_cache.cpp index f74e9a15ca..de4939428e 100644 --- a/moveit_ros/trajectory_cache/src/trajectory_cache.cpp +++ b/moveit_ros/trajectory_cache/src/trajectory_cache.cpp @@ -23,7 +23,7 @@ #include #include #include -#include +#include #include #include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h index 76dd1cd4e2..9f4fdbb32a 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include #include #include #include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame.cpp index 72850cf9e2..22590f8591 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame.cpp @@ -36,11 +36,11 @@ #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include #include @@ -57,7 +57,7 @@ #include #include -#include "ui_motion_planning_rviz_plugin_frame.h" +#include "ui_motion_planning_rviz_plugin_frame.hpp" namespace moveit_rviz_plugin { diff --git a/moveit_ros/visualization/robot_state_rviz_plugin/src/robot_state_display.cpp b/moveit_ros/visualization/robot_state_rviz_plugin/src/robot_state_display.cpp index c85f2ed3f1..5cedbd8def 100644 --- a/moveit_ros/visualization/robot_state_rviz_plugin/src/robot_state_display.cpp +++ b/moveit_ros/visualization/robot_state_rviz_plugin/src/robot_state_display.cpp @@ -34,9 +34,9 @@ /* Author: Ioan Sucan */ -#include -#include -#include +#include +#include +#include // #include #include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h index ada06febcb..95e3e32ea9 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h @@ -37,7 +37,7 @@ #pragma once #include -#include +#include namespace moveit_rviz_plugin { diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h index c7d7d3fcaf..2604aea953 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include #include #include #include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/src/render_shapes.cpp b/moveit_ros/visualization/rviz_plugin_render_tools/src/render_shapes.cpp index dc340cd4ae..7b93b0b7ce 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/src/render_shapes.cpp +++ b/moveit_ros/visualization/rviz_plugin_render_tools/src/render_shapes.cpp @@ -34,8 +34,8 @@ /* Author: Ioan Sucan */ -#include -#include +#include +#include #include #include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/src/robot_state_visualization.cpp b/moveit_ros/visualization/rviz_plugin_render_tools/src/robot_state_visualization.cpp index 7558fa7f23..a539292100 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/src/robot_state_visualization.cpp +++ b/moveit_ros/visualization/rviz_plugin_render_tools/src/robot_state_visualization.cpp @@ -34,9 +34,9 @@ /* Author: Ioan Sucan */ -#include -#include -#include +#include +#include +#include #include #include #include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/src/trajectory_panel.cpp b/moveit_ros/visualization/rviz_plugin_render_tools/src/trajectory_panel.cpp index d471818254..6a1872b433 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/src/trajectory_panel.cpp +++ b/moveit_ros/visualization/rviz_plugin_render_tools/src/trajectory_panel.cpp @@ -34,7 +34,7 @@ /* Author: Yannick Jonetzko */ -#include +#include #include namespace moveit_rviz_plugin diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/src/trajectory_visualization.cpp b/moveit_ros/visualization/rviz_plugin_render_tools/src/trajectory_visualization.cpp index aec921e06e..a60f7cbbe9 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/src/trajectory_visualization.cpp +++ b/moveit_ros/visualization/rviz_plugin_render_tools/src/trajectory_visualization.cpp @@ -37,13 +37,13 @@ #include #include -#include +#include -#include -#include +#include +#include #include #include -#include +#include #include #include #include diff --git a/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h b/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h index 4d15023463..3949bbb084 100644 --- a/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h +++ b/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h @@ -42,10 +42,10 @@ #include #include -#include +#include #ifndef Q_MOC_RUN #include -#include +#include #endif namespace rviz_common diff --git a/moveit_ros/visualization/trajectory_rviz_plugin/src/plugin_init.cpp b/moveit_ros/visualization/trajectory_rviz_plugin/src/plugin_init.cpp index db4d3ab851..31cd848596 100644 --- a/moveit_ros/visualization/trajectory_rviz_plugin/src/plugin_init.cpp +++ b/moveit_ros/visualization/trajectory_rviz_plugin/src/plugin_init.cpp @@ -35,6 +35,6 @@ /* Author: Dave Coleman */ #include -#include +#include CLASS_LOADER_REGISTER_CLASS(moveit_rviz_plugin::TrajectoryDisplay, rviz_common::Display) diff --git a/moveit_ros/visualization/trajectory_rviz_plugin/src/trajectory_display.cpp b/moveit_ros/visualization/trajectory_rviz_plugin/src/trajectory_display.cpp index da6d73de0c..78a13c718f 100644 --- a/moveit_ros/visualization/trajectory_rviz_plugin/src/trajectory_display.cpp +++ b/moveit_ros/visualization/trajectory_rviz_plugin/src/trajectory_display.cpp @@ -36,7 +36,7 @@ Desc: Wraps a trajectory_visualization playback class for Rviz into a stand alone display */ -#include +#include #include #include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h index 230b1c8555..3d99f27759 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h @@ -36,11 +36,11 @@ #pragma once -#include -#include +#include +#include #include -#include +#include #include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h index dd73ffa285..f672c5ec84 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h @@ -36,7 +36,7 @@ #pragma once -#include +#include #include #include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h index 8139c00ea8..47806c1986 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h @@ -36,14 +36,14 @@ #pragma once -#include -#include +#include +#include #include #include #include #include -#include +#include namespace moveit_warehouse { diff --git a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h index 4c17459656..ad5c207e5d 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h @@ -36,7 +36,7 @@ #pragma once -#include +#include #include #include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h index 58a8c91a70..7efe94d366 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h @@ -36,12 +36,12 @@ #pragma once -#include -#include +#include +#include #include #include -#include +#include namespace moveit_warehouse { diff --git a/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h index e729fac14c..dac9f36baa 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include #include #include diff --git a/moveit_ros/warehouse/src/broadcast.cpp b/moveit_ros/warehouse/src/broadcast.cpp index 7e17f6db14..a070e10be6 100644 --- a/moveit_ros/warehouse/src/broadcast.cpp +++ b/moveit_ros/warehouse/src/broadcast.cpp @@ -34,9 +34,9 @@ /* Author: Ioan Sucan */ -#include -#include -#include +#include +#include +#include #include #include #include diff --git a/moveit_ros/warehouse/src/constraints_storage.cpp b/moveit_ros/warehouse/src/constraints_storage.cpp index 9ec2b63b13..f38df9f067 100644 --- a/moveit_ros/warehouse/src/constraints_storage.cpp +++ b/moveit_ros/warehouse/src/constraints_storage.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include +#include #include #include diff --git a/moveit_ros/warehouse/src/import_from_text.cpp b/moveit_ros/warehouse/src/import_from_text.cpp index 6fa876220b..a33d2b328a 100644 --- a/moveit_ros/warehouse/src/import_from_text.cpp +++ b/moveit_ros/warehouse/src/import_from_text.cpp @@ -34,12 +34,12 @@ /* Author: Ioan Sucan */ -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include #include #include #include diff --git a/moveit_ros/warehouse/src/initialize_demo_db.cpp b/moveit_ros/warehouse/src/initialize_demo_db.cpp index 855714dcab..af3d047373 100644 --- a/moveit_ros/warehouse/src/initialize_demo_db.cpp +++ b/moveit_ros/warehouse/src/initialize_demo_db.cpp @@ -35,12 +35,12 @@ /* Author: Ioan Sucan */ #include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include #include #include #include diff --git a/moveit_ros/warehouse/src/moveit_message_storage.cpp b/moveit_ros/warehouse/src/moveit_message_storage.cpp index 3eb87f1352..127054c604 100644 --- a/moveit_ros/warehouse/src/moveit_message_storage.cpp +++ b/moveit_ros/warehouse/src/moveit_message_storage.cpp @@ -34,8 +34,8 @@ /* Author: Ioan Sucan */ -#include -#include +#include +#include #include #include #include diff --git a/moveit_ros/warehouse/src/planning_scene_storage.cpp b/moveit_ros/warehouse/src/planning_scene_storage.cpp index 5e861bd6eb..af622f8c9d 100644 --- a/moveit_ros/warehouse/src/planning_scene_storage.cpp +++ b/moveit_ros/warehouse/src/planning_scene_storage.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include +#include #include #include #include diff --git a/moveit_ros/warehouse/src/planning_scene_world_storage.cpp b/moveit_ros/warehouse/src/planning_scene_world_storage.cpp index f245d9b9f1..168e30011a 100644 --- a/moveit_ros/warehouse/src/planning_scene_world_storage.cpp +++ b/moveit_ros/warehouse/src/planning_scene_world_storage.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include +#include #include #include diff --git a/moveit_ros/warehouse/src/save_as_text.cpp b/moveit_ros/warehouse/src/save_as_text.cpp index 72592f9e7c..5fbe0433aa 100644 --- a/moveit_ros/warehouse/src/save_as_text.cpp +++ b/moveit_ros/warehouse/src/save_as_text.cpp @@ -34,15 +34,15 @@ /* Author: Ioan Sucan */ -#include -#include -#include +#include +#include +#include #include #include #include #include -#include -#include +#include +#include #include #include #include diff --git a/moveit_ros/warehouse/src/save_to_warehouse.cpp b/moveit_ros/warehouse/src/save_to_warehouse.cpp index 2e478afa38..b837cec649 100644 --- a/moveit_ros/warehouse/src/save_to_warehouse.cpp +++ b/moveit_ros/warehouse/src/save_to_warehouse.cpp @@ -34,10 +34,10 @@ /* Author: Ioan Sucan */ -#include -#include -#include -#include +#include +#include +#include +#include #include #include #include diff --git a/moveit_ros/warehouse/src/state_storage.cpp b/moveit_ros/warehouse/src/state_storage.cpp index 965aba9ccf..9eadb02fc8 100644 --- a/moveit_ros/warehouse/src/state_storage.cpp +++ b/moveit_ros/warehouse/src/state_storage.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan */ -#include +#include #include #include diff --git a/moveit_ros/warehouse/src/trajectory_constraints_storage.cpp b/moveit_ros/warehouse/src/trajectory_constraints_storage.cpp index b60c9233f8..dde199b3da 100644 --- a/moveit_ros/warehouse/src/trajectory_constraints_storage.cpp +++ b/moveit_ros/warehouse/src/trajectory_constraints_storage.cpp @@ -34,7 +34,7 @@ /* Author: Mario Prats, Ioan Sucan */ -#include +#include #include #include diff --git a/moveit_ros/warehouse/src/warehouse_connector.cpp b/moveit_ros/warehouse/src/warehouse_connector.cpp index d297652840..14b5ea70f8 100644 --- a/moveit_ros/warehouse/src/warehouse_connector.cpp +++ b/moveit_ros/warehouse/src/warehouse_connector.cpp @@ -36,7 +36,7 @@ #include #include -#include +#include #include #include #include diff --git a/moveit_ros/warehouse/src/warehouse_services.cpp b/moveit_ros/warehouse/src/warehouse_services.cpp index cae2de5823..e735c19425 100644 --- a/moveit_ros/warehouse/src/warehouse_services.cpp +++ b/moveit_ros/warehouse/src/warehouse_services.cpp @@ -34,7 +34,7 @@ /* Author: Dan Greenwald */ -#include +#include #include #include #include diff --git a/moveit_setup_assistant/moveit_setup_assistant/src/collisions_updater.cpp b/moveit_setup_assistant/moveit_setup_assistant/src/collisions_updater.cpp index d6c0eeb245..d8963e1be1 100644 --- a/moveit_setup_assistant/moveit_setup_assistant/src/collisions_updater.cpp +++ b/moveit_setup_assistant/moveit_setup_assistant/src/collisions_updater.cpp @@ -38,7 +38,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/src/controllers_widget.cpp b/moveit_setup_assistant/moveit_setup_controllers/src/controllers_widget.cpp index 9580de2b3c..770f1725d5 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/src/controllers_widget.cpp +++ b/moveit_setup_assistant/moveit_setup_controllers/src/controllers_widget.cpp @@ -56,7 +56,7 @@ #include #include -#include +#include namespace moveit_setup { diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.hpp b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.hpp index c3b444e205..4e066efdd9 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.hpp +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.hpp @@ -38,7 +38,7 @@ #include #include -#include +#include #include #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.hpp b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.hpp index c5ad29cbf0..92508e0251 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.hpp +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.hpp @@ -38,9 +38,9 @@ #include #include #include -#include -#include // for getting kinematic model -#include // for writing srdf data +#include +#include // for getting kinematic model +#include // for writing srdf data namespace moveit_setup { diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.hpp b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.hpp index 5c2c110dc9..e51521d02b 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.hpp +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.hpp @@ -35,7 +35,7 @@ /* Author: David V. Lu!! */ #include -#include +#include #include #include #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.hpp b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.hpp index 4f3288ead4..d476bcd38f 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.hpp +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.hpp @@ -37,7 +37,7 @@ #pragma once #include #include -#include +#include #include #include #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.hpp b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.hpp index e455d336ac..863a06b46b 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.hpp +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.hpp @@ -42,7 +42,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/moveit_setup_assistant/moveit_setup_framework/src/srdf_config.cpp b/moveit_setup_assistant/moveit_setup_framework/src/srdf_config.cpp index cfd7682978..d19bdbfa50 100644 --- a/moveit_setup_assistant/moveit_setup_framework/src/srdf_config.cpp +++ b/moveit_setup_assistant/moveit_setup_framework/src/srdf_config.cpp @@ -34,7 +34,7 @@ #include #include #include -#include +#include namespace moveit_setup { diff --git a/moveit_setup_assistant/moveit_setup_framework/src/urdf_config.cpp b/moveit_setup_assistant/moveit_setup_framework/src/urdf_config.cpp index 2480848908..72d9bf4af8 100644 --- a/moveit_setup_assistant/moveit_setup_framework/src/urdf_config.cpp +++ b/moveit_setup_assistant/moveit_setup_framework/src/urdf_config.cpp @@ -34,7 +34,7 @@ #include #include -#include +#include #include namespace moveit_setup diff --git a/moveit_setup_assistant/moveit_setup_simulation/src/simulation_widget.cpp b/moveit_setup_assistant/moveit_setup_simulation/src/simulation_widget.cpp index 51be95cf18..16920693cb 100644 --- a/moveit_setup_assistant/moveit_setup_simulation/src/simulation_widget.cpp +++ b/moveit_setup_assistant/moveit_setup_simulation/src/simulation_widget.cpp @@ -47,7 +47,7 @@ #include #include -#include +#include #include #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.hpp b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.hpp index 846b99cc5c..19f18e81b5 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.hpp +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.hpp @@ -37,7 +37,7 @@ #pragma once #include -#include +#include namespace planning_scene { MOVEIT_CLASS_FORWARD(PlanningScene); // Defines PlanningScenePtr, ConstPtr, WeakPtr... etc diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.hpp b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.hpp index f62880ae94..52dc4c8e8f 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.hpp +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.hpp @@ -37,7 +37,7 @@ #include #include -#include +#include #include namespace moveit_setup diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/src/compute_default_collisions.cpp b/moveit_setup_assistant/moveit_setup_srdf_plugins/src/compute_default_collisions.cpp index b45620a885..b481ce6a6c 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/src/compute_default_collisions.cpp +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/src/compute_default_collisions.cpp @@ -34,7 +34,7 @@ /* Author: Dave Coleman */ -#include +#include #include #include // for statistics at end #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/src/planning_groups.cpp b/moveit_setup_assistant/moveit_setup_srdf_plugins/src/planning_groups.cpp index 713cdd1fbb..1010a4d8e0 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/src/planning_groups.cpp +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/src/planning_groups.cpp @@ -35,7 +35,7 @@ /* Author: David V. Lu!! */ #include -#include +#include #include // for loading all avail kinematic planners //// Cycle checking diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/src/robot_poses.cpp b/moveit_setup_assistant/moveit_setup_srdf_plugins/src/robot_poses.cpp index 9e9529fbbd..2387ad6e55 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/src/robot_poses.cpp +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/src/robot_poses.cpp @@ -35,7 +35,7 @@ /* Author: David V. Lu!! */ #include -#include +#include namespace moveit_setup { From 3d8f70a716e93ce7706e4c5e1968258b5e1f3941 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Sun, 17 Nov 2024 16:18:57 +0000 Subject: [PATCH 03/53] Renames all .h files to .hpp --- ...cator_allvalid.h => collision_detector_allocator_allvalid.hpp} | 0 .../{collision_env_allvalid.h => collision_env_allvalid.hpp} | 0 .../{collision_common.h => collision_common.hpp} | 0 ...sion_detector_allocator.h => collision_detector_allocator.hpp} | 0 .../collision_detection/{collision_env.h => collision_env.hpp} | 0 .../{collision_matrix.h => collision_matrix.hpp} | 0 .../{collision_octomap_filter.h => collision_octomap_filter.hpp} | 0 .../{collision_plugin.h => collision_plugin.hpp} | 0 .../{collision_plugin_cache.h => collision_plugin_cache.hpp} | 0 .../{collision_tools.h => collision_tools.hpp} | 0 .../collision_detection/{occupancy_map.h => occupancy_map.hpp} | 0 ...t_collision_common_panda.h => test_collision_common_panda.hpp} | 0 ...{test_collision_common_pr2.h => test_collision_common_pr2.hpp} | 0 .../include/moveit/collision_detection/{world.h => world.hpp} | 0 .../moveit/collision_detection/{world_diff.h => world_diff.hpp} | 0 .../bullet_integration/{basic_types.h => basic_types.hpp} | 0 .../{bullet_bvh_manager.h => bullet_bvh_manager.hpp} | 0 .../{bullet_cast_bvh_manager.h => bullet_cast_bvh_manager.hpp} | 0 ...let_discrete_bvh_manager.h => bullet_discrete_bvh_manager.hpp} | 0 .../bullet_integration/{bullet_utils.h => bullet_utils.hpp} | 0 .../{contact_checker_common.h => contact_checker_common.hpp} | 0 .../{ros_bullet_utils.h => ros_bullet_utils.hpp} | 0 ...allocator_bullet.h => collision_detector_allocator_bullet.hpp} | 0 ...lugin_loader.h => collision_detector_bullet_plugin_loader.hpp} | 0 .../{collision_env_bullet.h => collision_env_bullet.hpp} | 0 .../{collision_common.h => collision_common.hpp} | 0 ...ector_allocator_fcl.h => collision_detector_allocator_fcl.hpp} | 0 ...l_plugin_loader.h => collision_detector_fcl_plugin_loader.hpp} | 0 .../{collision_env_fcl.h => collision_env_fcl.hpp} | 0 .../collision_detection_fcl/{fcl_compat.h => fcl_compat.hpp} | 0 ...ommon_distance_field.h => collision_common_distance_field.hpp} | 0 ...ce_field.h => collision_detector_allocator_distance_field.hpp} | 0 ...allocator_hybrid.h => collision_detector_allocator_hybrid.hpp} | 0 ..._distance_field_types.h => collision_distance_field_types.hpp} | 0 ...sion_env_distance_field.h => collision_env_distance_field.hpp} | 0 .../{collision_env_hybrid.h => collision_env_hybrid.hpp} | 0 .../{constraint_sampler.h => constraint_sampler.hpp} | 0 ...raint_sampler_allocator.h => constraint_sampler_allocator.hpp} | 0 ...onstraint_sampler_manager.h => constraint_sampler_manager.hpp} | 0 .../{constraint_sampler_tools.h => constraint_sampler_tools.hpp} | 0 ...ault_constraint_samplers.h => default_constraint_samplers.hpp} | 0 .../{union_constraint_sampler.h => union_constraint_sampler.hpp} | 0 .../constraint_samplers/test/{pr2_arm_ik.h => pr2_arm_ik.hpp} | 0 ...{pr2_arm_kinematics_plugin.h => pr2_arm_kinematics_plugin.hpp} | 0 .../{controller_manager.h => controller_manager.hpp} | 0 .../distance_field/{distance_field.h => distance_field.hpp} | 0 .../{find_internal_points.h => find_internal_points.hpp} | 0 ...ropagation_distance_field.h => propagation_distance_field.hpp} | 0 .../moveit/distance_field/{voxel_grid.h => voxel_grid.hpp} | 0 .../dynamics_solver/{dynamics_solver.h => dynamics_solver.hpp} | 0 .../include/moveit/exceptions/{exceptions.h => exceptions.hpp} | 0 .../{kinematic_constraint.h => kinematic_constraint.hpp} | 0 .../include/moveit/kinematic_constraints/{utils.h => utils.hpp} | 0 .../kinematics_base/{kinematics_base.h => kinematics_base.hpp} | 0 .../{kinematics_metrics.h => kinematics_metrics.hpp} | 0 .../include/moveit/macros/{class_forward.h => class_forward.hpp} | 0 .../moveit/macros/{console_colors.h => console_colors.hpp} | 0 .../include/moveit/macros/{declare_ptr.h => declare_ptr.hpp} | 0 .../include/moveit/macros/{deprecation.h => deprecation.hpp} | 0 .../{acceleration_filter.h => acceleration_filter.hpp} | 0 .../{butterworth_filter.h => butterworth_filter.hpp} | 0 .../{ruckig_filter.h => ruckig_filter.hpp} | 0 .../{smoothing_base_class.h => smoothing_base_class.hpp} | 0 .../{planning_interface.h => planning_interface.hpp} | 0 .../{planning_request.h => planning_request.hpp} | 0 .../{planning_request_adapter.h => planning_request_adapter.hpp} | 0 .../{planning_response.h => planning_response.hpp} | 0 ...{planning_response_adapter.h => planning_response_adapter.hpp} | 0 .../planning_scene/{planning_scene.h => planning_scene.hpp} | 0 .../robot_model/include/moveit/robot_model/{aabb.h => aabb.hpp} | 0 .../robot_model/{fixed_joint_model.h => fixed_joint_model.hpp} | 0 .../{floating_joint_model.h => floating_joint_model.hpp} | 0 .../include/moveit/robot_model/{joint_model.h => joint_model.hpp} | 0 .../robot_model/{joint_model_group.h => joint_model_group.hpp} | 0 .../include/moveit/robot_model/{link_model.h => link_model.hpp} | 0 .../robot_model/{planar_joint_model.h => planar_joint_model.hpp} | 0 .../{prismatic_joint_model.h => prismatic_joint_model.hpp} | 0 .../{revolute_joint_model.h => revolute_joint_model.hpp} | 0 .../include/moveit/robot_model/{robot_model.h => robot_model.hpp} | 0 .../moveit/robot_state/{attached_body.h => attached_body.hpp} | 0 .../{cartesian_interpolator.h => cartesian_interpolator.hpp} | 0 .../include/moveit/robot_state/{conversions.h => conversions.hpp} | 0 .../include/moveit/robot_state/{robot_state.h => robot_state.hpp} | 0 .../robot_trajectory/{robot_trajectory.h => robot_trajectory.hpp} | 0 .../{ruckig_traj_smoothing.h => ruckig_traj_smoothing.hpp} | 0 ...ectory_generation.h => time_optimal_trajectory_generation.hpp} | 0 .../{time_parameterization.h => time_parameterization.hpp} | 0 .../{trajectory_tools.h => trajectory_tools.hpp} | 0 .../include/moveit/transforms/{transforms.h => transforms.hpp} | 0 .../moveit/utils/{eigen_test_utils.h => eigen_test_utils.hpp} | 0 .../include/moveit/utils/{lexical_casts.h => lexical_casts.hpp} | 0 .../include/moveit/utils/{message_checks.h => message_checks.hpp} | 0 .../moveit/utils/{moveit_error_code.h => moveit_error_code.hpp} | 0 .../include/moveit/utils/{rclcpp_utils.h => rclcpp_utils.hpp} | 0 .../{robot_model_test_utils.h => robot_model_test_utils.hpp} | 0 ...inematics_plugin-inl.h => cached_ik_kinematics_plugin-inl.hpp} | 0 ...hed_ik_kinematics_plugin.h => cached_ik_kinematics_plugin.hpp} | 0 .../detail/{GreedyKCenters.h => GreedyKCenters.hpp} | 0 .../detail/{NearestNeighbors.h => NearestNeighbors.hpp} | 0 .../detail/{NearestNeighborsGNAT.h => NearestNeighborsGNAT.hpp} | 0 .../ikfast_kinematics_plugin/templates/{ikfast.h => ikfast.hpp} | 0 .../{kdl_kinematics_plugin.h => kdl_kinematics_plugin.hpp} | 0 .../{srv_kinematics_plugin.h => srv_kinematics_plugin.hpp} | 0 .../chomp_interface/{chomp_interface.h => chomp_interface.hpp} | 0 .../{chomp_planning_context.h => chomp_planning_context.hpp} | 0 .../include/chomp_motion_planner/{chomp_cost.h => chomp_cost.hpp} | 0 .../{chomp_optimizer.h => chomp_optimizer.hpp} | 0 .../{chomp_parameters.h => chomp_parameters.hpp} | 0 .../chomp_motion_planner/{chomp_planner.h => chomp_planner.hpp} | 0 .../{chomp_trajectory.h => chomp_trajectory.hpp} | 0 .../chomp_motion_planner/{chomp_utils.h => chomp_utils.hpp} | 0 .../{multivariate_gaussian.h => multivariate_gaussian.hpp} | 0 .../{constrained_goal_sampler.h => constrained_goal_sampler.hpp} | 0 .../detail/{constrained_sampler.h => constrained_sampler.hpp} | 0 ...{constraint_approximations.h => constraint_approximations.hpp} | 0 .../detail/{constraints_library.h => constraints_library.hpp} | 0 .../moveit/ompl_interface/detail/{goal_union.h => goal_union.hpp} | 0 .../detail/{ompl_constraints.h => ompl_constraints.hpp} | 0 .../detail/{projection_evaluators.h => projection_evaluators.hpp} | 0 .../{state_validity_checker.h => state_validity_checker.hpp} | 0 .../{threadsafe_state_storage.h => threadsafe_state_storage.hpp} | 0 ..._based_planning_context.h => model_based_planning_context.hpp} | 0 .../ompl_interface/{ompl_interface.h => ompl_interface.hpp} | 0 ...lanning_state_space.h => constrained_planning_state_space.hpp} | 0 ...ace_factory.h => constrained_planning_state_space_factory.hpp} | 0 .../{joint_model_state_space.h => joint_model_state_space.hpp} | 0 ..._state_space_factory.h => joint_model_state_space_factory.hpp} | 0 .../{model_based_state_space.h => model_based_state_space.hpp} | 0 ..._state_space_factory.h => model_based_state_space_factory.hpp} | 0 .../{pose_model_state_space.h => pose_model_state_space.hpp} | 0 ...l_state_space_factory.h => pose_model_state_space_factory.hpp} | 0 .../{planning_context_manager.h => planning_context_manager.hpp} | 0 .../test/{load_test_robot.h => load_test_robot.hpp} | 0 .../{capability_names.h => capability_names.hpp} | 0 .../{cartesian_trajectory.h => cartesian_trajectory.hpp} | 0 ...artesian_trajectory_point.h => cartesian_trajectory_point.hpp} | 0 .../{command_list_manager.h => command_list_manager.hpp} | 0 .../{joint_limits_aggregator.h => joint_limits_aggregator.hpp} | 0 .../{joint_limits_container.h => joint_limits_container.hpp} | 0 .../{joint_limits_extension.h => joint_limits_extension.hpp} | 0 ...interface_extension.h => joint_limits_interface_extension.hpp} | 0 .../{joint_limits_validator.h => joint_limits_validator.hpp} | 0 .../{limits_container.h => limits_container.hpp} | 0 ...ove_group_sequence_action.h => move_group_sequence_action.hpp} | 0 ...e_group_sequence_service.h => move_group_sequence_service.hpp} | 0 .../{path_circle_generator.h => path_circle_generator.hpp} | 0 ...strial_motion_planner.h => pilz_industrial_motion_planner.hpp} | 0 .../{plan_components_builder.h => plan_components_builder.hpp} | 0 .../{planning_context_base.h => planning_context_base.hpp} | 0 .../{planning_context_circ.h => planning_context_circ.hpp} | 0 .../{planning_context_lin.h => planning_context_lin.hpp} | 0 .../{planning_context_loader.h => planning_context_loader.hpp} | 0 ...ing_context_loader_circ.h => planning_context_loader_circ.hpp} | 0 ...nning_context_loader_lin.h => planning_context_loader_lin.hpp} | 0 ...nning_context_loader_ptp.h => planning_context_loader_ptp.hpp} | 0 .../{planning_context_ptp.h => planning_context_ptp.hpp} | 0 .../{planning_exceptions.h => planning_exceptions.hpp} | 0 .../{tip_frame_getter.h => tip_frame_getter.hpp} | 0 .../{trajectory_blend_request.h => trajectory_blend_request.hpp} | 0 ...{trajectory_blend_response.h => trajectory_blend_response.hpp} | 0 .../{trajectory_blender.h => trajectory_blender.hpp} | 0 ...ansition_window.h => trajectory_blender_transition_window.hpp} | 0 .../{trajectory_functions.h => trajectory_functions.hpp} | 0 ...neration_exceptions.h => trajectory_generation_exceptions.hpp} | 0 .../{trajectory_generator.h => trajectory_generator.hpp} | 0 ...{trajectory_generator_circ.h => trajectory_generator_circ.hpp} | 0 .../{trajectory_generator_lin.h => trajectory_generator_lin.hpp} | 0 .../{trajectory_generator_ptp.h => trajectory_generator_ptp.hpp} | 0 .../{velocity_profile_atrap.h => velocity_profile_atrap.hpp} | 0 .../test/{test_utils.h => test_utils.hpp} | 0 .../{async_test.h => async_test.hpp} | 0 .../{basecmd.h => basecmd.hpp} | 0 .../{cartesianconfiguration.h => cartesianconfiguration.hpp} | 0 ...thconstraintsbuilder.h => cartesianpathconstraintsbuilder.hpp} | 0 .../{center.h => center.hpp} | 0 .../{checks.h => checks.hpp} | 0 .../pilz_industrial_motion_planner_testutils/{circ.h => circ.hpp} | 0 .../{circ_auxiliary_types.h => circ_auxiliary_types.hpp} | 0 .../{circauxiliary.h => circauxiliary.hpp} | 0 .../{command_types_typedef.h => command_types_typedef.hpp} | 0 .../{default_values.h => default_values.hpp} | 0 .../{exception_types.h => exception_types.hpp} | 0 ...straintsmsgconvertible.h => goalconstraintsmsgconvertible.hpp} | 0 .../{gripper.h => gripper.hpp} | 0 .../{interim.h => interim.hpp} | 0 .../{jointconfiguration.h => jointconfiguration.hpp} | 0 .../pilz_industrial_motion_planner_testutils/{lin.h => lin.hpp} | 0 .../{motioncmd.h => motioncmd.hpp} | 0 ...nplanrequestconvertible.h => motionplanrequestconvertible.hpp} | 0 .../pilz_industrial_motion_planner_testutils/{ptp.h => ptp.hpp} | 0 .../{robotconfiguration.h => robotconfiguration.hpp} | 0 .../{robotstatemsgconvertible.h => robotstatemsgconvertible.hpp} | 0 .../{sequence.h => sequence.hpp} | 0 .../{testdata_loader.h => testdata_loader.hpp} | 0 .../{xml_constants.h => xml_constants.hpp} | 0 .../{xml_testdata_loader.h => xml_testdata_loader.hpp} | 0 .../include/{ikfast.h => ikfast.hpp} | 0 .../{ControllerHandle.h => ControllerHandle.hpp} | 0 ...sed_controller_handle.h => action_based_controller_handle.hpp} | 0 .../{empty_controller_handle.h => empty_controller_handle.hpp} | 0 ...ler_handle.h => follow_joint_trajectory_controller_handle.hpp} | 0 ...{gripper_controller_handle.h => gripper_controller_handle.hpp} | 0 .../{collision_common.h => collision_common.hpp} | 0 .../{collision_matrix.h => collision_matrix.hpp} | 0 .../moveit/moveit_core/collision_detection/{world.h => world.hpp} | 0 .../{controller_manager.h => controller_manager.hpp} | 0 .../moveit_core/kinematic_constraints/{utils.h => utils.hpp} | 0 .../{planning_response.h => planning_response.hpp} | 0 .../planning_scene/{planning_scene.h => planning_scene.hpp} | 0 .../moveit_core/robot_model/{joint_model.h => joint_model.hpp} | 0 .../robot_model/{joint_model_group.h => joint_model_group.hpp} | 0 .../moveit_core/robot_model/{robot_model.h => robot_model.hpp} | 0 .../moveit_core/robot_state/{robot_state.h => robot_state.hpp} | 0 .../robot_trajectory/{robot_trajectory.h => robot_trajectory.hpp} | 0 .../moveit_core/transforms/{transforms.h => transforms.hpp} | 0 .../moveit_py_utils/{copy_ros_msg.h => copy_ros_msg.hpp} | 0 .../{ros_msg_typecasters.h => ros_msg_typecasters.hpp} | 0 .../moveit/moveit_ros/moveit_cpp/{moveit_cpp.h => moveit_cpp.hpp} | 0 .../moveit_cpp/{planning_component.h => planning_component.hpp} | 0 .../{planning_scene_monitor.h => planning_scene_monitor.hpp} | 0 ...ctory_execution_manager.h => trajectory_execution_manager.hpp} | 0 .../benchmarks/{BenchmarkExecutor.h => BenchmarkExecutor.hpp} | 0 .../benchmarks/{BenchmarkOptions.h => BenchmarkOptions.hpp} | 0 .../{global_planner_component.h => global_planner_component.hpp} | 0 .../{global_planner_interface.h => global_planner_interface.hpp} | 0 .../{moveit_planning_pipeline.h => moveit_planning_pipeline.hpp} | 0 .../{hybrid_planning_events.h => hybrid_planning_events.hpp} | 0 .../{hybrid_planning_manager.h => hybrid_planning_manager.hpp} | 0 .../{planner_logic_interface.h => planner_logic_interface.hpp} | 0 ...invalidated_trajectory.h => replan_invalidated_trajectory.hpp} | 0 .../{single_plan_execution.h => single_plan_execution.hpp} | 0 .../{forward_trajectory.h => forward_trajectory.hpp} | 0 .../moveit/local_planner/{feedback_types.h => feedback_types.hpp} | 0 ...t_solver_interface.h => local_constraint_solver_interface.hpp} | 0 .../{local_planner_component.h => local_planner_component.hpp} | 0 ...ory_operator_interface.h => trajectory_operator_interface.hpp} | 0 .../{simple_sampler.h => simple_sampler.hpp} | 0 .../move_group/{capability_names.h => capability_names.hpp} | 0 .../{move_group_capability.h => move_group_capability.hpp} | 0 .../move_group/{move_group_context.h => move_group_context.hpp} | 0 ...e_capability.h => apply_planning_scene_service_capability.hpp} | 0 ...service_capability.h => cartesian_path_service_capability.hpp} | 0 ..._service_capability.h => clear_octomap_service_capability.hpp} | 0 ...tion_capability.h => execute_trajectory_action_capability.hpp} | 0 ...{get_group_urdf_capability.h => get_group_urdf_capability.hpp} | 0 ...ice_capability.h => get_planning_scene_service_capability.hpp} | 0 ...ics_service_capability.h => kinematics_service_capability.hpp} | 0 ...apability.h => load_geometry_from_file_service_capability.hpp} | 0 .../{move_action_capability.h => move_action_capability.hpp} | 0 .../{plan_service_capability.h => plan_service_capability.hpp} | 0 ...service_capability.h => query_planners_service_capability.hpp} | 0 ..._capability.h => save_geometry_to_file_service_capability.hpp} | 0 ...rvice_capability.h => state_validation_service_capability.hpp} | 0 .../{tf_publisher_capability.h => tf_publisher_capability.hpp} | 0 .../{occupancy_map_monitor.h => occupancy_map_monitor.hpp} | 0 .../{occupancy_map_updater.h => occupancy_map_updater.hpp} | 0 ...th_image_octomap_updater.h => depth_image_octomap_updater.hpp} | 0 .../{lazy_free_space_updater.h => lazy_free_space_updater.hpp} | 0 ...{depth_self_filter_nodelet.h => depth_self_filter_nodelet.hpp} | 0 .../include/moveit/mesh_filter/{filter_job.h => filter_job.hpp} | 0 .../include/moveit/mesh_filter/{gl_mesh.h => gl_mesh.hpp} | 0 .../include/moveit/mesh_filter/{gl_renderer.h => gl_renderer.hpp} | 0 .../include/moveit/mesh_filter/{mesh_filter.h => mesh_filter.hpp} | 0 .../mesh_filter/{mesh_filter_base.h => mesh_filter_base.hpp} | 0 .../moveit/mesh_filter/{sensor_model.h => sensor_model.hpp} | 0 .../{stereo_camera_model.h => stereo_camera_model.hpp} | 0 .../mesh_filter/{transform_provider.h => transform_provider.hpp} | 0 .../point_containment_filter/{shape_mask.h => shape_mask.hpp} | 0 ...ointcloud_octomap_updater.h => pointcloud_octomap_updater.hpp} | 0 .../semantic_world/{semantic_world.h => semantic_world.hpp} | 0 .../{collision_plugin_loader.h => collision_plugin_loader.hpp} | 0 ...ler_manager_loader.h => constraint_sampler_manager_loader.hpp} | 0 .../{kinematics_plugin_loader.h => kinematics_plugin_loader.hpp} | 0 .../include/moveit/moveit_cpp/{moveit_cpp.h => moveit_cpp.hpp} | 0 .../moveit_cpp/{planning_component.h => planning_component.hpp} | 0 .../plan_execution/{plan_execution.h => plan_execution.hpp} | 0 .../{plan_representation.h => plan_representation.hpp} | 0 .../{planning_pipeline.h => planning_pipeline.hpp} | 0 .../{current_state_monitor.h => current_state_monitor.hpp} | 0 .../{planning_scene_monitor.h => planning_scene_monitor.hpp} | 0 .../{trajectory_monitor.h => trajectory_monitor.hpp} | 0 .../include/moveit/rdf_loader/{rdf_loader.h => rdf_loader.hpp} | 0 ...nized_string_parameter.h => synchronized_string_parameter.hpp} | 0 .../{robot_model_loader.h => robot_model_loader.hpp} | 0 ...ctory_execution_manager.h => trajectory_execution_manager.hpp} | 0 ...it_controller_manager.h => test_moveit_controller_manager.hpp} | 0 .../{common_objects.h => common_objects.hpp} | 0 .../{move_group_interface.h => move_group_interface.hpp} | 0 .../{planning_scene_interface.h => planning_scene_interface.hpp} | 0 .../moveit/robot_interaction/{interaction.h => interaction.hpp} | 0 .../{interaction_handler.h => interaction_handler.hpp} | 0 ...nteractive_marker_helpers.h => interactive_marker_helpers.hpp} | 0 .../{kinematic_options.h => kinematic_options.hpp} | 0 .../{kinematic_options_map.h => kinematic_options_map.hpp} | 0 .../{locked_robot_state.h => locked_robot_state.hpp} | 0 .../{robot_interaction.h => robot_interaction.hpp} | 0 ...nteractive_marker_display.h => interactive_marker_display.hpp} | 0 .../{motion_planning_display.h => motion_planning_display.hpp} | 0 .../{motion_planning_frame.h => motion_planning_frame.hpp} | 0 ...me_joints_widget.h => motion_planning_frame_joints_widget.hpp} | 0 ...n_planning_param_widget.h => motion_planning_param_widget.hpp} | 0 .../{planning_scene_display.h => planning_scene_display.hpp} | 0 .../{robot_state_display.h => robot_state_display.hpp} | 0 .../{octomap_render.h => octomap_render.hpp} | 0 .../{planning_link_updater.h => planning_link_updater.hpp} | 0 .../{planning_scene_render.h => planning_scene_render.hpp} | 0 .../{render_shapes.h => render_shapes.hpp} | 0 ...{robot_state_visualization.h => robot_state_visualization.hpp} | 0 .../{trajectory_panel.h => trajectory_panel.hpp} | 0 .../{trajectory_visualization.h => trajectory_visualization.hpp} | 0 .../{trajectory_display.h => trajectory_display.hpp} | 0 .../warehouse/{constraints_storage.h => constraints_storage.hpp} | 0 .../{moveit_message_storage.h => moveit_message_storage.hpp} | 0 .../{planning_scene_storage.h => planning_scene_storage.hpp} | 0 ...ing_scene_world_storage.h => planning_scene_world_storage.hpp} | 0 .../moveit/warehouse/{state_storage.h => state_storage.hpp} | 0 ...y_constraints_storage.h => trajectory_constraints_storage.hpp} | 0 .../warehouse/{warehouse_connector.h => warehouse_connector.hpp} | 0 318 files changed, 0 insertions(+), 0 deletions(-) rename moveit_core/collision_detection/include/moveit/collision_detection/allvalid/{collision_detector_allocator_allvalid.h => collision_detector_allocator_allvalid.hpp} (100%) rename moveit_core/collision_detection/include/moveit/collision_detection/allvalid/{collision_env_allvalid.h => collision_env_allvalid.hpp} (100%) rename moveit_core/collision_detection/include/moveit/collision_detection/{collision_common.h => collision_common.hpp} (100%) rename moveit_core/collision_detection/include/moveit/collision_detection/{collision_detector_allocator.h => collision_detector_allocator.hpp} (100%) rename moveit_core/collision_detection/include/moveit/collision_detection/{collision_env.h => collision_env.hpp} (100%) rename moveit_core/collision_detection/include/moveit/collision_detection/{collision_matrix.h => collision_matrix.hpp} (100%) rename moveit_core/collision_detection/include/moveit/collision_detection/{collision_octomap_filter.h => collision_octomap_filter.hpp} (100%) rename moveit_core/collision_detection/include/moveit/collision_detection/{collision_plugin.h => collision_plugin.hpp} (100%) rename moveit_core/collision_detection/include/moveit/collision_detection/{collision_plugin_cache.h => collision_plugin_cache.hpp} (100%) rename moveit_core/collision_detection/include/moveit/collision_detection/{collision_tools.h => collision_tools.hpp} (100%) rename moveit_core/collision_detection/include/moveit/collision_detection/{occupancy_map.h => occupancy_map.hpp} (100%) rename moveit_core/collision_detection/include/moveit/collision_detection/{test_collision_common_panda.h => test_collision_common_panda.hpp} (100%) rename moveit_core/collision_detection/include/moveit/collision_detection/{test_collision_common_pr2.h => test_collision_common_pr2.hpp} (100%) rename moveit_core/collision_detection/include/moveit/collision_detection/{world.h => world.hpp} (100%) rename moveit_core/collision_detection/include/moveit/collision_detection/{world_diff.h => world_diff.hpp} (100%) rename moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/{basic_types.h => basic_types.hpp} (100%) rename moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/{bullet_bvh_manager.h => bullet_bvh_manager.hpp} (100%) rename moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/{bullet_cast_bvh_manager.h => bullet_cast_bvh_manager.hpp} (100%) rename moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/{bullet_discrete_bvh_manager.h => bullet_discrete_bvh_manager.hpp} (100%) rename moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/{bullet_utils.h => bullet_utils.hpp} (100%) rename moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/{contact_checker_common.h => contact_checker_common.hpp} (100%) rename moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/{ros_bullet_utils.h => ros_bullet_utils.hpp} (100%) rename moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/{collision_detector_allocator_bullet.h => collision_detector_allocator_bullet.hpp} (100%) rename moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/{collision_detector_bullet_plugin_loader.h => collision_detector_bullet_plugin_loader.hpp} (100%) rename moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/{collision_env_bullet.h => collision_env_bullet.hpp} (100%) rename moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/{collision_common.h => collision_common.hpp} (100%) rename moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/{collision_detector_allocator_fcl.h => collision_detector_allocator_fcl.hpp} (100%) rename moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/{collision_detector_fcl_plugin_loader.h => collision_detector_fcl_plugin_loader.hpp} (100%) rename moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/{collision_env_fcl.h => collision_env_fcl.hpp} (100%) rename moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/{fcl_compat.h => fcl_compat.hpp} (100%) rename moveit_core/collision_distance_field/include/moveit/collision_distance_field/{collision_common_distance_field.h => collision_common_distance_field.hpp} (100%) rename moveit_core/collision_distance_field/include/moveit/collision_distance_field/{collision_detector_allocator_distance_field.h => collision_detector_allocator_distance_field.hpp} (100%) rename moveit_core/collision_distance_field/include/moveit/collision_distance_field/{collision_detector_allocator_hybrid.h => collision_detector_allocator_hybrid.hpp} (100%) rename moveit_core/collision_distance_field/include/moveit/collision_distance_field/{collision_distance_field_types.h => collision_distance_field_types.hpp} (100%) rename moveit_core/collision_distance_field/include/moveit/collision_distance_field/{collision_env_distance_field.h => collision_env_distance_field.hpp} (100%) rename moveit_core/collision_distance_field/include/moveit/collision_distance_field/{collision_env_hybrid.h => collision_env_hybrid.hpp} (100%) rename moveit_core/constraint_samplers/include/moveit/constraint_samplers/{constraint_sampler.h => constraint_sampler.hpp} (100%) rename moveit_core/constraint_samplers/include/moveit/constraint_samplers/{constraint_sampler_allocator.h => constraint_sampler_allocator.hpp} (100%) rename moveit_core/constraint_samplers/include/moveit/constraint_samplers/{constraint_sampler_manager.h => constraint_sampler_manager.hpp} (100%) rename moveit_core/constraint_samplers/include/moveit/constraint_samplers/{constraint_sampler_tools.h => constraint_sampler_tools.hpp} (100%) rename moveit_core/constraint_samplers/include/moveit/constraint_samplers/{default_constraint_samplers.h => default_constraint_samplers.hpp} (100%) rename moveit_core/constraint_samplers/include/moveit/constraint_samplers/{union_constraint_sampler.h => union_constraint_sampler.hpp} (100%) rename moveit_core/constraint_samplers/test/{pr2_arm_ik.h => pr2_arm_ik.hpp} (100%) rename moveit_core/constraint_samplers/test/{pr2_arm_kinematics_plugin.h => pr2_arm_kinematics_plugin.hpp} (100%) rename moveit_core/controller_manager/include/moveit/controller_manager/{controller_manager.h => controller_manager.hpp} (100%) rename moveit_core/distance_field/include/moveit/distance_field/{distance_field.h => distance_field.hpp} (100%) rename moveit_core/distance_field/include/moveit/distance_field/{find_internal_points.h => find_internal_points.hpp} (100%) rename moveit_core/distance_field/include/moveit/distance_field/{propagation_distance_field.h => propagation_distance_field.hpp} (100%) rename moveit_core/distance_field/include/moveit/distance_field/{voxel_grid.h => voxel_grid.hpp} (100%) rename moveit_core/dynamics_solver/include/moveit/dynamics_solver/{dynamics_solver.h => dynamics_solver.hpp} (100%) rename moveit_core/exceptions/include/moveit/exceptions/{exceptions.h => exceptions.hpp} (100%) rename moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/{kinematic_constraint.h => kinematic_constraint.hpp} (100%) rename moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/{utils.h => utils.hpp} (100%) rename moveit_core/kinematics_base/include/moveit/kinematics_base/{kinematics_base.h => kinematics_base.hpp} (100%) rename moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/{kinematics_metrics.h => kinematics_metrics.hpp} (100%) rename moveit_core/macros/include/moveit/macros/{class_forward.h => class_forward.hpp} (100%) rename moveit_core/macros/include/moveit/macros/{console_colors.h => console_colors.hpp} (100%) rename moveit_core/macros/include/moveit/macros/{declare_ptr.h => declare_ptr.hpp} (100%) rename moveit_core/macros/include/moveit/macros/{deprecation.h => deprecation.hpp} (100%) rename moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/{acceleration_filter.h => acceleration_filter.hpp} (100%) rename moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/{butterworth_filter.h => butterworth_filter.hpp} (100%) rename moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/{ruckig_filter.h => ruckig_filter.hpp} (100%) rename moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/{smoothing_base_class.h => smoothing_base_class.hpp} (100%) rename moveit_core/planning_interface/include/moveit/planning_interface/{planning_interface.h => planning_interface.hpp} (100%) rename moveit_core/planning_interface/include/moveit/planning_interface/{planning_request.h => planning_request.hpp} (100%) rename moveit_core/planning_interface/include/moveit/planning_interface/{planning_request_adapter.h => planning_request_adapter.hpp} (100%) rename moveit_core/planning_interface/include/moveit/planning_interface/{planning_response.h => planning_response.hpp} (100%) rename moveit_core/planning_interface/include/moveit/planning_interface/{planning_response_adapter.h => planning_response_adapter.hpp} (100%) rename moveit_core/planning_scene/include/moveit/planning_scene/{planning_scene.h => planning_scene.hpp} (100%) rename moveit_core/robot_model/include/moveit/robot_model/{aabb.h => aabb.hpp} (100%) rename moveit_core/robot_model/include/moveit/robot_model/{fixed_joint_model.h => fixed_joint_model.hpp} (100%) rename moveit_core/robot_model/include/moveit/robot_model/{floating_joint_model.h => floating_joint_model.hpp} (100%) rename moveit_core/robot_model/include/moveit/robot_model/{joint_model.h => joint_model.hpp} (100%) rename moveit_core/robot_model/include/moveit/robot_model/{joint_model_group.h => joint_model_group.hpp} (100%) rename moveit_core/robot_model/include/moveit/robot_model/{link_model.h => link_model.hpp} (100%) rename moveit_core/robot_model/include/moveit/robot_model/{planar_joint_model.h => planar_joint_model.hpp} (100%) rename moveit_core/robot_model/include/moveit/robot_model/{prismatic_joint_model.h => prismatic_joint_model.hpp} (100%) rename moveit_core/robot_model/include/moveit/robot_model/{revolute_joint_model.h => revolute_joint_model.hpp} (100%) rename moveit_core/robot_model/include/moveit/robot_model/{robot_model.h => robot_model.hpp} (100%) rename moveit_core/robot_state/include/moveit/robot_state/{attached_body.h => attached_body.hpp} (100%) rename moveit_core/robot_state/include/moveit/robot_state/{cartesian_interpolator.h => cartesian_interpolator.hpp} (100%) rename moveit_core/robot_state/include/moveit/robot_state/{conversions.h => conversions.hpp} (100%) rename moveit_core/robot_state/include/moveit/robot_state/{robot_state.h => robot_state.hpp} (100%) rename moveit_core/robot_trajectory/include/moveit/robot_trajectory/{robot_trajectory.h => robot_trajectory.hpp} (100%) rename moveit_core/trajectory_processing/include/moveit/trajectory_processing/{ruckig_traj_smoothing.h => ruckig_traj_smoothing.hpp} (100%) rename moveit_core/trajectory_processing/include/moveit/trajectory_processing/{time_optimal_trajectory_generation.h => time_optimal_trajectory_generation.hpp} (100%) rename moveit_core/trajectory_processing/include/moveit/trajectory_processing/{time_parameterization.h => time_parameterization.hpp} (100%) rename moveit_core/trajectory_processing/include/moveit/trajectory_processing/{trajectory_tools.h => trajectory_tools.hpp} (100%) rename moveit_core/transforms/include/moveit/transforms/{transforms.h => transforms.hpp} (100%) rename moveit_core/utils/include/moveit/utils/{eigen_test_utils.h => eigen_test_utils.hpp} (100%) rename moveit_core/utils/include/moveit/utils/{lexical_casts.h => lexical_casts.hpp} (100%) rename moveit_core/utils/include/moveit/utils/{message_checks.h => message_checks.hpp} (100%) rename moveit_core/utils/include/moveit/utils/{moveit_error_code.h => moveit_error_code.hpp} (100%) rename moveit_core/utils/include/moveit/utils/{rclcpp_utils.h => rclcpp_utils.hpp} (100%) rename moveit_core/utils/include/moveit/utils/{robot_model_test_utils.h => robot_model_test_utils.hpp} (100%) rename moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/{cached_ik_kinematics_plugin-inl.h => cached_ik_kinematics_plugin-inl.hpp} (100%) rename moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/{cached_ik_kinematics_plugin.h => cached_ik_kinematics_plugin.hpp} (100%) rename moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/{GreedyKCenters.h => GreedyKCenters.hpp} (100%) rename moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/{NearestNeighbors.h => NearestNeighbors.hpp} (100%) rename moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/{NearestNeighborsGNAT.h => NearestNeighborsGNAT.hpp} (100%) rename moveit_kinematics/ikfast_kinematics_plugin/templates/{ikfast.h => ikfast.hpp} (100%) rename moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/{kdl_kinematics_plugin.h => kdl_kinematics_plugin.hpp} (100%) rename moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/{srv_kinematics_plugin.h => srv_kinematics_plugin.hpp} (100%) rename moveit_planners/chomp/chomp_interface/include/chomp_interface/{chomp_interface.h => chomp_interface.hpp} (100%) rename moveit_planners/chomp/chomp_interface/include/chomp_interface/{chomp_planning_context.h => chomp_planning_context.hpp} (100%) rename moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/{chomp_cost.h => chomp_cost.hpp} (100%) rename moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/{chomp_optimizer.h => chomp_optimizer.hpp} (100%) rename moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/{chomp_parameters.h => chomp_parameters.hpp} (100%) rename moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/{chomp_planner.h => chomp_planner.hpp} (100%) rename moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/{chomp_trajectory.h => chomp_trajectory.hpp} (100%) rename moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/{chomp_utils.h => chomp_utils.hpp} (100%) rename moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/{multivariate_gaussian.h => multivariate_gaussian.hpp} (100%) rename moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/{constrained_goal_sampler.h => constrained_goal_sampler.hpp} (100%) rename moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/{constrained_sampler.h => constrained_sampler.hpp} (100%) rename moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/{constraint_approximations.h => constraint_approximations.hpp} (100%) rename moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/{constraints_library.h => constraints_library.hpp} (100%) rename moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/{goal_union.h => goal_union.hpp} (100%) rename moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/{ompl_constraints.h => ompl_constraints.hpp} (100%) rename moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/{projection_evaluators.h => projection_evaluators.hpp} (100%) rename moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/{state_validity_checker.h => state_validity_checker.hpp} (100%) rename moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/{threadsafe_state_storage.h => threadsafe_state_storage.hpp} (100%) rename moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/{model_based_planning_context.h => model_based_planning_context.hpp} (100%) rename moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/{ompl_interface.h => ompl_interface.hpp} (100%) rename moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/{constrained_planning_state_space.h => constrained_planning_state_space.hpp} (100%) rename moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/{constrained_planning_state_space_factory.h => constrained_planning_state_space_factory.hpp} (100%) rename moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/{joint_model_state_space.h => joint_model_state_space.hpp} (100%) rename moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/{joint_model_state_space_factory.h => joint_model_state_space_factory.hpp} (100%) rename moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/{model_based_state_space.h => model_based_state_space.hpp} (100%) rename moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/{model_based_state_space_factory.h => model_based_state_space_factory.hpp} (100%) rename moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/{pose_model_state_space.h => pose_model_state_space.hpp} (100%) rename moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/{pose_model_state_space_factory.h => pose_model_state_space_factory.hpp} (100%) rename moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/{planning_context_manager.h => planning_context_manager.hpp} (100%) rename moveit_planners/ompl/ompl_interface/test/{load_test_robot.h => load_test_robot.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{capability_names.h => capability_names.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{cartesian_trajectory.h => cartesian_trajectory.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{cartesian_trajectory_point.h => cartesian_trajectory_point.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{command_list_manager.h => command_list_manager.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{joint_limits_aggregator.h => joint_limits_aggregator.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{joint_limits_container.h => joint_limits_container.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{joint_limits_extension.h => joint_limits_extension.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{joint_limits_interface_extension.h => joint_limits_interface_extension.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{joint_limits_validator.h => joint_limits_validator.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{limits_container.h => limits_container.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{move_group_sequence_action.h => move_group_sequence_action.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{move_group_sequence_service.h => move_group_sequence_service.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{path_circle_generator.h => path_circle_generator.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{pilz_industrial_motion_planner.h => pilz_industrial_motion_planner.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{plan_components_builder.h => plan_components_builder.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{planning_context_base.h => planning_context_base.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{planning_context_circ.h => planning_context_circ.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{planning_context_lin.h => planning_context_lin.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{planning_context_loader.h => planning_context_loader.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{planning_context_loader_circ.h => planning_context_loader_circ.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{planning_context_loader_lin.h => planning_context_loader_lin.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{planning_context_loader_ptp.h => planning_context_loader_ptp.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{planning_context_ptp.h => planning_context_ptp.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{planning_exceptions.h => planning_exceptions.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{tip_frame_getter.h => tip_frame_getter.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{trajectory_blend_request.h => trajectory_blend_request.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{trajectory_blend_response.h => trajectory_blend_response.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{trajectory_blender.h => trajectory_blender.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{trajectory_blender_transition_window.h => trajectory_blender_transition_window.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{trajectory_functions.h => trajectory_functions.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{trajectory_generation_exceptions.h => trajectory_generation_exceptions.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{trajectory_generator.h => trajectory_generator.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{trajectory_generator_circ.h => trajectory_generator_circ.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{trajectory_generator_lin.h => trajectory_generator_lin.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{trajectory_generator_ptp.h => trajectory_generator_ptp.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/{velocity_profile_atrap.h => velocity_profile_atrap.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner/test/{test_utils.h => test_utils.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/{async_test.h => async_test.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/{basecmd.h => basecmd.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/{cartesianconfiguration.h => cartesianconfiguration.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/{cartesianpathconstraintsbuilder.h => cartesianpathconstraintsbuilder.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/{center.h => center.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/{checks.h => checks.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/{circ.h => circ.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/{circ_auxiliary_types.h => circ_auxiliary_types.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/{circauxiliary.h => circauxiliary.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/{command_types_typedef.h => command_types_typedef.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/{default_values.h => default_values.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/{exception_types.h => exception_types.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/{goalconstraintsmsgconvertible.h => goalconstraintsmsgconvertible.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/{gripper.h => gripper.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/{interim.h => interim.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/{jointconfiguration.h => jointconfiguration.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/{lin.h => lin.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/{motioncmd.h => motioncmd.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/{motionplanrequestconvertible.h => motionplanrequestconvertible.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/{ptp.h => ptp.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/{robotconfiguration.h => robotconfiguration.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/{robotstatemsgconvertible.h => robotstatemsgconvertible.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/{sequence.h => sequence.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/{testdata_loader.h => testdata_loader.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/{xml_constants.h => xml_constants.hpp} (100%) rename moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/{xml_testdata_loader.h => xml_testdata_loader.hpp} (100%) rename moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/include/{ikfast.h => ikfast.hpp} (100%) rename moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/{ControllerHandle.h => ControllerHandle.hpp} (100%) rename moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/{action_based_controller_handle.h => action_based_controller_handle.hpp} (100%) rename moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/{empty_controller_handle.h => empty_controller_handle.hpp} (100%) rename moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/{follow_joint_trajectory_controller_handle.h => follow_joint_trajectory_controller_handle.hpp} (100%) rename moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/{gripper_controller_handle.h => gripper_controller_handle.hpp} (100%) rename moveit_py/src/moveit/moveit_core/collision_detection/{collision_common.h => collision_common.hpp} (100%) rename moveit_py/src/moveit/moveit_core/collision_detection/{collision_matrix.h => collision_matrix.hpp} (100%) rename moveit_py/src/moveit/moveit_core/collision_detection/{world.h => world.hpp} (100%) rename moveit_py/src/moveit/moveit_core/controller_manager/{controller_manager.h => controller_manager.hpp} (100%) rename moveit_py/src/moveit/moveit_core/kinematic_constraints/{utils.h => utils.hpp} (100%) rename moveit_py/src/moveit/moveit_core/planning_interface/{planning_response.h => planning_response.hpp} (100%) rename moveit_py/src/moveit/moveit_core/planning_scene/{planning_scene.h => planning_scene.hpp} (100%) rename moveit_py/src/moveit/moveit_core/robot_model/{joint_model.h => joint_model.hpp} (100%) rename moveit_py/src/moveit/moveit_core/robot_model/{joint_model_group.h => joint_model_group.hpp} (100%) rename moveit_py/src/moveit/moveit_core/robot_model/{robot_model.h => robot_model.hpp} (100%) rename moveit_py/src/moveit/moveit_core/robot_state/{robot_state.h => robot_state.hpp} (100%) rename moveit_py/src/moveit/moveit_core/robot_trajectory/{robot_trajectory.h => robot_trajectory.hpp} (100%) rename moveit_py/src/moveit/moveit_core/transforms/{transforms.h => transforms.hpp} (100%) rename moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/{copy_ros_msg.h => copy_ros_msg.hpp} (100%) rename moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/{ros_msg_typecasters.h => ros_msg_typecasters.hpp} (100%) rename moveit_py/src/moveit/moveit_ros/moveit_cpp/{moveit_cpp.h => moveit_cpp.hpp} (100%) rename moveit_py/src/moveit/moveit_ros/moveit_cpp/{planning_component.h => planning_component.hpp} (100%) rename moveit_py/src/moveit/moveit_ros/planning_scene_monitor/{planning_scene_monitor.h => planning_scene_monitor.hpp} (100%) rename moveit_py/src/moveit/moveit_ros/trajectory_execution_manager/{trajectory_execution_manager.h => trajectory_execution_manager.hpp} (100%) rename moveit_ros/benchmarks/include/moveit/benchmarks/{BenchmarkExecutor.h => BenchmarkExecutor.hpp} (100%) rename moveit_ros/benchmarks/include/moveit/benchmarks/{BenchmarkOptions.h => BenchmarkOptions.hpp} (100%) rename moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/{global_planner_component.h => global_planner_component.hpp} (100%) rename moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/{global_planner_interface.h => global_planner_interface.hpp} (100%) rename moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/{moveit_planning_pipeline.h => moveit_planning_pipeline.hpp} (100%) rename moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/{hybrid_planning_events.h => hybrid_planning_events.hpp} (100%) rename moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/{hybrid_planning_manager.h => hybrid_planning_manager.hpp} (100%) rename moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/{planner_logic_interface.h => planner_logic_interface.hpp} (100%) rename moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/{replan_invalidated_trajectory.h => replan_invalidated_trajectory.hpp} (100%) rename moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/{single_plan_execution.h => single_plan_execution.hpp} (100%) rename moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/{forward_trajectory.h => forward_trajectory.hpp} (100%) rename moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/{feedback_types.h => feedback_types.hpp} (100%) rename moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/{local_constraint_solver_interface.h => local_constraint_solver_interface.hpp} (100%) rename moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/{local_planner_component.h => local_planner_component.hpp} (100%) rename moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/{trajectory_operator_interface.h => trajectory_operator_interface.hpp} (100%) rename moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/{simple_sampler.h => simple_sampler.hpp} (100%) rename moveit_ros/move_group/include/moveit/move_group/{capability_names.h => capability_names.hpp} (100%) rename moveit_ros/move_group/include/moveit/move_group/{move_group_capability.h => move_group_capability.hpp} (100%) rename moveit_ros/move_group/include/moveit/move_group/{move_group_context.h => move_group_context.hpp} (100%) rename moveit_ros/move_group/src/default_capabilities/{apply_planning_scene_service_capability.h => apply_planning_scene_service_capability.hpp} (100%) rename moveit_ros/move_group/src/default_capabilities/{cartesian_path_service_capability.h => cartesian_path_service_capability.hpp} (100%) rename moveit_ros/move_group/src/default_capabilities/{clear_octomap_service_capability.h => clear_octomap_service_capability.hpp} (100%) rename moveit_ros/move_group/src/default_capabilities/{execute_trajectory_action_capability.h => execute_trajectory_action_capability.hpp} (100%) rename moveit_ros/move_group/src/default_capabilities/{get_group_urdf_capability.h => get_group_urdf_capability.hpp} (100%) rename moveit_ros/move_group/src/default_capabilities/{get_planning_scene_service_capability.h => get_planning_scene_service_capability.hpp} (100%) rename moveit_ros/move_group/src/default_capabilities/{kinematics_service_capability.h => kinematics_service_capability.hpp} (100%) rename moveit_ros/move_group/src/default_capabilities/{load_geometry_from_file_service_capability.h => load_geometry_from_file_service_capability.hpp} (100%) rename moveit_ros/move_group/src/default_capabilities/{move_action_capability.h => move_action_capability.hpp} (100%) rename moveit_ros/move_group/src/default_capabilities/{plan_service_capability.h => plan_service_capability.hpp} (100%) rename moveit_ros/move_group/src/default_capabilities/{query_planners_service_capability.h => query_planners_service_capability.hpp} (100%) rename moveit_ros/move_group/src/default_capabilities/{save_geometry_to_file_service_capability.h => save_geometry_to_file_service_capability.hpp} (100%) rename moveit_ros/move_group/src/default_capabilities/{state_validation_service_capability.h => state_validation_service_capability.hpp} (100%) rename moveit_ros/move_group/src/default_capabilities/{tf_publisher_capability.h => tf_publisher_capability.hpp} (100%) rename moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/{occupancy_map_monitor.h => occupancy_map_monitor.hpp} (100%) rename moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/{occupancy_map_updater.h => occupancy_map_updater.hpp} (100%) rename moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/{depth_image_octomap_updater.h => depth_image_octomap_updater.hpp} (100%) rename moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/{lazy_free_space_updater.h => lazy_free_space_updater.hpp} (100%) rename moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/{depth_self_filter_nodelet.h => depth_self_filter_nodelet.hpp} (100%) rename moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/{filter_job.h => filter_job.hpp} (100%) rename moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/{gl_mesh.h => gl_mesh.hpp} (100%) rename moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/{gl_renderer.h => gl_renderer.hpp} (100%) rename moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/{mesh_filter.h => mesh_filter.hpp} (100%) rename moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/{mesh_filter_base.h => mesh_filter_base.hpp} (100%) rename moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/{sensor_model.h => sensor_model.hpp} (100%) rename moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/{stereo_camera_model.h => stereo_camera_model.hpp} (100%) rename moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/{transform_provider.h => transform_provider.hpp} (100%) rename moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/{shape_mask.h => shape_mask.hpp} (100%) rename moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/{pointcloud_octomap_updater.h => pointcloud_octomap_updater.hpp} (100%) rename moveit_ros/perception/semantic_world/include/moveit/semantic_world/{semantic_world.h => semantic_world.hpp} (100%) rename moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/{collision_plugin_loader.h => collision_plugin_loader.hpp} (100%) rename moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/{constraint_sampler_manager_loader.h => constraint_sampler_manager_loader.hpp} (100%) rename moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/{kinematics_plugin_loader.h => kinematics_plugin_loader.hpp} (100%) rename moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/{moveit_cpp.h => moveit_cpp.hpp} (100%) rename moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/{planning_component.h => planning_component.hpp} (100%) rename moveit_ros/planning/plan_execution/include/moveit/plan_execution/{plan_execution.h => plan_execution.hpp} (100%) rename moveit_ros/planning/plan_execution/include/moveit/plan_execution/{plan_representation.h => plan_representation.hpp} (100%) rename moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/{planning_pipeline.h => planning_pipeline.hpp} (100%) rename moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/{current_state_monitor.h => current_state_monitor.hpp} (100%) rename moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/{planning_scene_monitor.h => planning_scene_monitor.hpp} (100%) rename moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/{trajectory_monitor.h => trajectory_monitor.hpp} (100%) rename moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/{rdf_loader.h => rdf_loader.hpp} (100%) rename moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/{synchronized_string_parameter.h => synchronized_string_parameter.hpp} (100%) rename moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/{robot_model_loader.h => robot_model_loader.hpp} (100%) rename moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/{trajectory_execution_manager.h => trajectory_execution_manager.hpp} (100%) rename moveit_ros/planning/trajectory_execution_manager/test/{test_moveit_controller_manager.h => test_moveit_controller_manager.hpp} (100%) rename moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/{common_objects.h => common_objects.hpp} (100%) rename moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/{move_group_interface.h => move_group_interface.hpp} (100%) rename moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/{planning_scene_interface.h => planning_scene_interface.hpp} (100%) rename moveit_ros/robot_interaction/include/moveit/robot_interaction/{interaction.h => interaction.hpp} (100%) rename moveit_ros/robot_interaction/include/moveit/robot_interaction/{interaction_handler.h => interaction_handler.hpp} (100%) rename moveit_ros/robot_interaction/include/moveit/robot_interaction/{interactive_marker_helpers.h => interactive_marker_helpers.hpp} (100%) rename moveit_ros/robot_interaction/include/moveit/robot_interaction/{kinematic_options.h => kinematic_options.hpp} (100%) rename moveit_ros/robot_interaction/include/moveit/robot_interaction/{kinematic_options_map.h => kinematic_options_map.hpp} (100%) rename moveit_ros/robot_interaction/include/moveit/robot_interaction/{locked_robot_state.h => locked_robot_state.hpp} (100%) rename moveit_ros/robot_interaction/include/moveit/robot_interaction/{robot_interaction.h => robot_interaction.hpp} (100%) rename moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/{interactive_marker_display.h => interactive_marker_display.hpp} (100%) rename moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/{motion_planning_display.h => motion_planning_display.hpp} (100%) rename moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/{motion_planning_frame.h => motion_planning_frame.hpp} (100%) rename moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/{motion_planning_frame_joints_widget.h => motion_planning_frame_joints_widget.hpp} (100%) rename moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/{motion_planning_param_widget.h => motion_planning_param_widget.hpp} (100%) rename moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/{planning_scene_display.h => planning_scene_display.hpp} (100%) rename moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/{robot_state_display.h => robot_state_display.hpp} (100%) rename moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/{octomap_render.h => octomap_render.hpp} (100%) rename moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/{planning_link_updater.h => planning_link_updater.hpp} (100%) rename moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/{planning_scene_render.h => planning_scene_render.hpp} (100%) rename moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/{render_shapes.h => render_shapes.hpp} (100%) rename moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/{robot_state_visualization.h => robot_state_visualization.hpp} (100%) rename moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/{trajectory_panel.h => trajectory_panel.hpp} (100%) rename moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/{trajectory_visualization.h => trajectory_visualization.hpp} (100%) rename moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/{trajectory_display.h => trajectory_display.hpp} (100%) rename moveit_ros/warehouse/include/moveit/warehouse/{constraints_storage.h => constraints_storage.hpp} (100%) rename moveit_ros/warehouse/include/moveit/warehouse/{moveit_message_storage.h => moveit_message_storage.hpp} (100%) rename moveit_ros/warehouse/include/moveit/warehouse/{planning_scene_storage.h => planning_scene_storage.hpp} (100%) rename moveit_ros/warehouse/include/moveit/warehouse/{planning_scene_world_storage.h => planning_scene_world_storage.hpp} (100%) rename moveit_ros/warehouse/include/moveit/warehouse/{state_storage.h => state_storage.hpp} (100%) rename moveit_ros/warehouse/include/moveit/warehouse/{trajectory_constraints_storage.h => trajectory_constraints_storage.hpp} (100%) rename moveit_ros/warehouse/include/moveit/warehouse/{warehouse_connector.h => warehouse_connector.hpp} (100%) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.hpp similarity index 100% rename from moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h rename to moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.hpp diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.hpp similarity index 100% rename from moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h rename to moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.hpp diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.hpp similarity index 100% rename from moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h rename to moveit_core/collision_detection/include/moveit/collision_detection/collision_common.hpp diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.hpp similarity index 100% rename from moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h rename to moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.hpp diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.hpp similarity index 100% rename from moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h rename to moveit_core/collision_detection/include/moveit/collision_detection/collision_env.hpp diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.hpp similarity index 100% rename from moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h rename to moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.hpp diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.hpp similarity index 100% rename from moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h rename to moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.hpp diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.hpp similarity index 100% rename from moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h rename to moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.hpp diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.hpp similarity index 100% rename from moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h rename to moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.hpp diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.hpp similarity index 100% rename from moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h rename to moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.hpp diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h b/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.hpp similarity index 100% rename from moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h rename to moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.hpp diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.hpp similarity index 100% rename from moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h rename to moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.hpp diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.hpp similarity index 100% rename from moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h rename to moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.hpp diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/world.h b/moveit_core/collision_detection/include/moveit/collision_detection/world.hpp similarity index 100% rename from moveit_core/collision_detection/include/moveit/collision_detection/world.h rename to moveit_core/collision_detection/include/moveit/collision_detection/world.hpp diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h b/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.hpp similarity index 100% rename from moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h rename to moveit_core/collision_detection/include/moveit/collision_detection/world_diff.hpp diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.hpp similarity index 100% rename from moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h rename to moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.hpp diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.hpp similarity index 100% rename from moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h rename to moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.hpp diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.hpp similarity index 100% rename from moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h rename to moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.hpp diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.hpp similarity index 100% rename from moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h rename to moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.hpp diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.hpp similarity index 100% rename from moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h rename to moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.hpp diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.hpp similarity index 100% rename from moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h rename to moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.hpp diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.hpp similarity index 100% rename from moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h rename to moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.hpp diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.hpp similarity index 100% rename from moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h rename to moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.hpp diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.hpp similarity index 100% rename from moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h rename to moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.hpp diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.hpp similarity index 100% rename from moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h rename to moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.hpp diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.hpp similarity index 100% rename from moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h rename to moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.hpp diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.hpp similarity index 100% rename from moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h rename to moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.hpp diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.hpp similarity index 100% rename from moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h rename to moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.hpp diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.hpp similarity index 100% rename from moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h rename to moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.hpp diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.hpp similarity index 100% rename from moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h rename to moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.hpp diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.hpp similarity index 100% rename from moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h rename to moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.hpp diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.hpp similarity index 100% rename from moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h rename to moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.hpp diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.hpp similarity index 100% rename from moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h rename to moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.hpp diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.hpp similarity index 100% rename from moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h rename to moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.hpp diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.hpp similarity index 100% rename from moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h rename to moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.hpp diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.hpp similarity index 100% rename from moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h rename to moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.hpp diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.hpp similarity index 100% rename from moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h rename to moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.hpp diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.hpp similarity index 100% rename from moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h rename to moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.hpp diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.hpp similarity index 100% rename from moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h rename to moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.hpp diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.hpp similarity index 100% rename from moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h rename to moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.hpp diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.hpp similarity index 100% rename from moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h rename to moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.hpp diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.hpp similarity index 100% rename from moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h rename to moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.hpp diff --git a/moveit_core/constraint_samplers/test/pr2_arm_ik.h b/moveit_core/constraint_samplers/test/pr2_arm_ik.hpp similarity index 100% rename from moveit_core/constraint_samplers/test/pr2_arm_ik.h rename to moveit_core/constraint_samplers/test/pr2_arm_ik.hpp diff --git a/moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.h b/moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.hpp similarity index 100% rename from moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.h rename to moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.hpp diff --git a/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h b/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.hpp similarity index 100% rename from moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h rename to moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.hpp diff --git a/moveit_core/distance_field/include/moveit/distance_field/distance_field.h b/moveit_core/distance_field/include/moveit/distance_field/distance_field.hpp similarity index 100% rename from moveit_core/distance_field/include/moveit/distance_field/distance_field.h rename to moveit_core/distance_field/include/moveit/distance_field/distance_field.hpp diff --git a/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h b/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.hpp similarity index 100% rename from moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h rename to moveit_core/distance_field/include/moveit/distance_field/find_internal_points.hpp diff --git a/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h b/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.hpp similarity index 100% rename from moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h rename to moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.hpp diff --git a/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h b/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.hpp similarity index 100% rename from moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h rename to moveit_core/distance_field/include/moveit/distance_field/voxel_grid.hpp diff --git a/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h b/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.hpp similarity index 100% rename from moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h rename to moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.hpp diff --git a/moveit_core/exceptions/include/moveit/exceptions/exceptions.h b/moveit_core/exceptions/include/moveit/exceptions/exceptions.hpp similarity index 100% rename from moveit_core/exceptions/include/moveit/exceptions/exceptions.h rename to moveit_core/exceptions/include/moveit/exceptions/exceptions.hpp diff --git a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.hpp similarity index 100% rename from moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h rename to moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.hpp diff --git a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.hpp similarity index 100% rename from moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h rename to moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.hpp diff --git a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.hpp similarity index 100% rename from moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h rename to moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.hpp diff --git a/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h b/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.hpp similarity index 100% rename from moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h rename to moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.hpp diff --git a/moveit_core/macros/include/moveit/macros/class_forward.h b/moveit_core/macros/include/moveit/macros/class_forward.hpp similarity index 100% rename from moveit_core/macros/include/moveit/macros/class_forward.h rename to moveit_core/macros/include/moveit/macros/class_forward.hpp diff --git a/moveit_core/macros/include/moveit/macros/console_colors.h b/moveit_core/macros/include/moveit/macros/console_colors.hpp similarity index 100% rename from moveit_core/macros/include/moveit/macros/console_colors.h rename to moveit_core/macros/include/moveit/macros/console_colors.hpp diff --git a/moveit_core/macros/include/moveit/macros/declare_ptr.h b/moveit_core/macros/include/moveit/macros/declare_ptr.hpp similarity index 100% rename from moveit_core/macros/include/moveit/macros/declare_ptr.h rename to moveit_core/macros/include/moveit/macros/declare_ptr.hpp diff --git a/moveit_core/macros/include/moveit/macros/deprecation.h b/moveit_core/macros/include/moveit/macros/deprecation.hpp similarity index 100% rename from moveit_core/macros/include/moveit/macros/deprecation.h rename to moveit_core/macros/include/moveit/macros/deprecation.hpp diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.hpp similarity index 100% rename from moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h rename to moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.hpp diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.hpp similarity index 100% rename from moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h rename to moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.hpp diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.hpp similarity index 100% rename from moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h rename to moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.hpp diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.hpp similarity index 100% rename from moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h rename to moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.hpp diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.hpp similarity index 100% rename from moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h rename to moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.hpp diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.hpp similarity index 100% rename from moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h rename to moveit_core/planning_interface/include/moveit/planning_interface/planning_request.hpp diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.hpp similarity index 100% rename from moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h rename to moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.hpp diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.hpp similarity index 100% rename from moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h rename to moveit_core/planning_interface/include/moveit/planning_interface/planning_response.hpp diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.hpp similarity index 100% rename from moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h rename to moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.hpp diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.hpp similarity index 100% rename from moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h rename to moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.hpp diff --git a/moveit_core/robot_model/include/moveit/robot_model/aabb.h b/moveit_core/robot_model/include/moveit/robot_model/aabb.hpp similarity index 100% rename from moveit_core/robot_model/include/moveit/robot_model/aabb.h rename to moveit_core/robot_model/include/moveit/robot_model/aabb.hpp diff --git a/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.hpp similarity index 100% rename from moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h rename to moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.hpp diff --git a/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.hpp similarity index 100% rename from moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h rename to moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.hpp diff --git a/moveit_core/robot_model/include/moveit/robot_model/joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/joint_model.hpp similarity index 100% rename from moveit_core/robot_model/include/moveit/robot_model/joint_model.h rename to moveit_core/robot_model/include/moveit/robot_model/joint_model.hpp diff --git a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.hpp similarity index 100% rename from moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h rename to moveit_core/robot_model/include/moveit/robot_model/joint_model_group.hpp diff --git a/moveit_core/robot_model/include/moveit/robot_model/link_model.h b/moveit_core/robot_model/include/moveit/robot_model/link_model.hpp similarity index 100% rename from moveit_core/robot_model/include/moveit/robot_model/link_model.h rename to moveit_core/robot_model/include/moveit/robot_model/link_model.hpp diff --git a/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.hpp similarity index 100% rename from moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h rename to moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.hpp diff --git a/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.hpp similarity index 100% rename from moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h rename to moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.hpp diff --git a/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.hpp similarity index 100% rename from moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h rename to moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.hpp diff --git a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h b/moveit_core/robot_model/include/moveit/robot_model/robot_model.hpp similarity index 100% rename from moveit_core/robot_model/include/moveit/robot_model/robot_model.h rename to moveit_core/robot_model/include/moveit/robot_model/robot_model.hpp diff --git a/moveit_core/robot_state/include/moveit/robot_state/attached_body.h b/moveit_core/robot_state/include/moveit/robot_state/attached_body.hpp similarity index 100% rename from moveit_core/robot_state/include/moveit/robot_state/attached_body.h rename to moveit_core/robot_state/include/moveit/robot_state/attached_body.hpp diff --git a/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h b/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.hpp similarity index 100% rename from moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h rename to moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.hpp diff --git a/moveit_core/robot_state/include/moveit/robot_state/conversions.h b/moveit_core/robot_state/include/moveit/robot_state/conversions.hpp similarity index 100% rename from moveit_core/robot_state/include/moveit/robot_state/conversions.h rename to moveit_core/robot_state/include/moveit/robot_state/conversions.hpp diff --git a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h b/moveit_core/robot_state/include/moveit/robot_state/robot_state.hpp similarity index 100% rename from moveit_core/robot_state/include/moveit/robot_state/robot_state.h rename to moveit_core/robot_state/include/moveit/robot_state/robot_state.hpp diff --git a/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.hpp similarity index 100% rename from moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h rename to moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.hpp diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.hpp similarity index 100% rename from moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h rename to moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.hpp diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.hpp similarity index 100% rename from moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h rename to moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.hpp diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.hpp similarity index 100% rename from moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h rename to moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.hpp diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.hpp similarity index 100% rename from moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h rename to moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.hpp diff --git a/moveit_core/transforms/include/moveit/transforms/transforms.h b/moveit_core/transforms/include/moveit/transforms/transforms.hpp similarity index 100% rename from moveit_core/transforms/include/moveit/transforms/transforms.h rename to moveit_core/transforms/include/moveit/transforms/transforms.hpp diff --git a/moveit_core/utils/include/moveit/utils/eigen_test_utils.h b/moveit_core/utils/include/moveit/utils/eigen_test_utils.hpp similarity index 100% rename from moveit_core/utils/include/moveit/utils/eigen_test_utils.h rename to moveit_core/utils/include/moveit/utils/eigen_test_utils.hpp diff --git a/moveit_core/utils/include/moveit/utils/lexical_casts.h b/moveit_core/utils/include/moveit/utils/lexical_casts.hpp similarity index 100% rename from moveit_core/utils/include/moveit/utils/lexical_casts.h rename to moveit_core/utils/include/moveit/utils/lexical_casts.hpp diff --git a/moveit_core/utils/include/moveit/utils/message_checks.h b/moveit_core/utils/include/moveit/utils/message_checks.hpp similarity index 100% rename from moveit_core/utils/include/moveit/utils/message_checks.h rename to moveit_core/utils/include/moveit/utils/message_checks.hpp diff --git a/moveit_core/utils/include/moveit/utils/moveit_error_code.h b/moveit_core/utils/include/moveit/utils/moveit_error_code.hpp similarity index 100% rename from moveit_core/utils/include/moveit/utils/moveit_error_code.h rename to moveit_core/utils/include/moveit/utils/moveit_error_code.hpp diff --git a/moveit_core/utils/include/moveit/utils/rclcpp_utils.h b/moveit_core/utils/include/moveit/utils/rclcpp_utils.hpp similarity index 100% rename from moveit_core/utils/include/moveit/utils/rclcpp_utils.h rename to moveit_core/utils/include/moveit/utils/rclcpp_utils.hpp diff --git a/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h b/moveit_core/utils/include/moveit/utils/robot_model_test_utils.hpp similarity index 100% rename from moveit_core/utils/include/moveit/utils/robot_model_test_utils.h rename to moveit_core/utils/include/moveit/utils/robot_model_test_utils.hpp diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.hpp similarity index 100% rename from moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h rename to moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.hpp diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.hpp similarity index 100% rename from moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h rename to moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.hpp diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.hpp similarity index 100% rename from moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h rename to moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.hpp diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.hpp similarity index 100% rename from moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h rename to moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.hpp diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.hpp similarity index 100% rename from moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h rename to moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.hpp diff --git a/moveit_kinematics/ikfast_kinematics_plugin/templates/ikfast.h b/moveit_kinematics/ikfast_kinematics_plugin/templates/ikfast.hpp similarity index 100% rename from moveit_kinematics/ikfast_kinematics_plugin/templates/ikfast.h rename to moveit_kinematics/ikfast_kinematics_plugin/templates/ikfast.hpp diff --git a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.hpp similarity index 100% rename from moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h rename to moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.hpp diff --git a/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h b/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.hpp similarity index 100% rename from moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h rename to moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.hpp diff --git a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.hpp similarity index 100% rename from moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h rename to moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.hpp diff --git a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.hpp similarity index 100% rename from moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h rename to moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.hpp diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.hpp similarity index 100% rename from moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h rename to moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.hpp diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.hpp similarity index 100% rename from moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h rename to moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.hpp diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.hpp similarity index 100% rename from moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h rename to moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.hpp diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.hpp similarity index 100% rename from moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h rename to moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.hpp diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.hpp similarity index 100% rename from moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h rename to moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.hpp diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.hpp similarity index 100% rename from moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h rename to moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.hpp diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.hpp similarity index 100% rename from moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h rename to moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.hpp diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.hpp similarity index 100% rename from moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h rename to moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.hpp diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.hpp similarity index 100% rename from moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h rename to moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.hpp diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.hpp similarity index 100% rename from moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h rename to moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.hpp diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.hpp similarity index 100% rename from moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h rename to moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.hpp diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.hpp similarity index 100% rename from moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h rename to moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.hpp diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.hpp similarity index 100% rename from moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h rename to moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.hpp diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.hpp similarity index 100% rename from moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h rename to moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.hpp diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.hpp similarity index 100% rename from moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h rename to moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.hpp diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.hpp similarity index 100% rename from moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h rename to moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.hpp diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.hpp similarity index 100% rename from moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h rename to moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.hpp diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.hpp similarity index 100% rename from moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h rename to moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.hpp diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.hpp similarity index 100% rename from moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h rename to moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.hpp diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.hpp similarity index 100% rename from moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h rename to moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.hpp diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.hpp similarity index 100% rename from moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h rename to moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.hpp diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.hpp similarity index 100% rename from moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h rename to moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.hpp diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.hpp similarity index 100% rename from moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h rename to moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.hpp diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.hpp similarity index 100% rename from moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h rename to moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.hpp diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.hpp similarity index 100% rename from moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h rename to moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.hpp diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.hpp similarity index 100% rename from moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h rename to moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.hpp diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.hpp similarity index 100% rename from moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h rename to moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.hpp diff --git a/moveit_planners/ompl/ompl_interface/test/load_test_robot.h b/moveit_planners/ompl/ompl_interface/test/load_test_robot.hpp similarity index 100% rename from moveit_planners/ompl/ompl_interface/test/load_test_robot.h rename to moveit_planners/ompl/ompl_interface/test/load_test_robot.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h rename to moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner/test/test_utils.h b/moveit_planners/pilz_industrial_motion_planner/test/test_utils.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner/test/test_utils.h rename to moveit_planners/pilz_industrial_motion_planner/test/test_utils.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h rename to moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h rename to moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h rename to moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h rename to moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h rename to moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h rename to moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h rename to moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h rename to moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h rename to moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h rename to moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h rename to moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h rename to moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h rename to moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h rename to moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h rename to moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h rename to moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h rename to moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h rename to moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h rename to moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h rename to moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h rename to moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h rename to moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h rename to moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h rename to moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h rename to moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.hpp diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.hpp similarity index 100% rename from moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h rename to moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.hpp diff --git a/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/include/ikfast.h b/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/include/ikfast.hpp similarity index 100% rename from moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/include/ikfast.h rename to moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/include/ikfast.hpp diff --git a/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h b/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.hpp similarity index 100% rename from moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h rename to moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.hpp diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.hpp similarity index 100% rename from moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h rename to moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.hpp diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.hpp similarity index 100% rename from moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h rename to moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.hpp diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.hpp similarity index 100% rename from moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h rename to moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.hpp diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.hpp similarity index 100% rename from moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h rename to moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.hpp diff --git a/moveit_py/src/moveit/moveit_core/collision_detection/collision_common.h b/moveit_py/src/moveit/moveit_core/collision_detection/collision_common.hpp similarity index 100% rename from moveit_py/src/moveit/moveit_core/collision_detection/collision_common.h rename to moveit_py/src/moveit/moveit_core/collision_detection/collision_common.hpp diff --git a/moveit_py/src/moveit/moveit_core/collision_detection/collision_matrix.h b/moveit_py/src/moveit/moveit_core/collision_detection/collision_matrix.hpp similarity index 100% rename from moveit_py/src/moveit/moveit_core/collision_detection/collision_matrix.h rename to moveit_py/src/moveit/moveit_core/collision_detection/collision_matrix.hpp diff --git a/moveit_py/src/moveit/moveit_core/collision_detection/world.h b/moveit_py/src/moveit/moveit_core/collision_detection/world.hpp similarity index 100% rename from moveit_py/src/moveit/moveit_core/collision_detection/world.h rename to moveit_py/src/moveit/moveit_core/collision_detection/world.hpp diff --git a/moveit_py/src/moveit/moveit_core/controller_manager/controller_manager.h b/moveit_py/src/moveit/moveit_core/controller_manager/controller_manager.hpp similarity index 100% rename from moveit_py/src/moveit/moveit_core/controller_manager/controller_manager.h rename to moveit_py/src/moveit/moveit_core/controller_manager/controller_manager.hpp diff --git a/moveit_py/src/moveit/moveit_core/kinematic_constraints/utils.h b/moveit_py/src/moveit/moveit_core/kinematic_constraints/utils.hpp similarity index 100% rename from moveit_py/src/moveit/moveit_core/kinematic_constraints/utils.h rename to moveit_py/src/moveit/moveit_core/kinematic_constraints/utils.hpp diff --git a/moveit_py/src/moveit/moveit_core/planning_interface/planning_response.h b/moveit_py/src/moveit/moveit_core/planning_interface/planning_response.hpp similarity index 100% rename from moveit_py/src/moveit/moveit_core/planning_interface/planning_response.h rename to moveit_py/src/moveit/moveit_core/planning_interface/planning_response.hpp diff --git a/moveit_py/src/moveit/moveit_core/planning_scene/planning_scene.h b/moveit_py/src/moveit/moveit_core/planning_scene/planning_scene.hpp similarity index 100% rename from moveit_py/src/moveit/moveit_core/planning_scene/planning_scene.h rename to moveit_py/src/moveit/moveit_core/planning_scene/planning_scene.hpp diff --git a/moveit_py/src/moveit/moveit_core/robot_model/joint_model.h b/moveit_py/src/moveit/moveit_core/robot_model/joint_model.hpp similarity index 100% rename from moveit_py/src/moveit/moveit_core/robot_model/joint_model.h rename to moveit_py/src/moveit/moveit_core/robot_model/joint_model.hpp diff --git a/moveit_py/src/moveit/moveit_core/robot_model/joint_model_group.h b/moveit_py/src/moveit/moveit_core/robot_model/joint_model_group.hpp similarity index 100% rename from moveit_py/src/moveit/moveit_core/robot_model/joint_model_group.h rename to moveit_py/src/moveit/moveit_core/robot_model/joint_model_group.hpp diff --git a/moveit_py/src/moveit/moveit_core/robot_model/robot_model.h b/moveit_py/src/moveit/moveit_core/robot_model/robot_model.hpp similarity index 100% rename from moveit_py/src/moveit/moveit_core/robot_model/robot_model.h rename to moveit_py/src/moveit/moveit_core/robot_model/robot_model.hpp diff --git a/moveit_py/src/moveit/moveit_core/robot_state/robot_state.h b/moveit_py/src/moveit/moveit_core/robot_state/robot_state.hpp similarity index 100% rename from moveit_py/src/moveit/moveit_core/robot_state/robot_state.h rename to moveit_py/src/moveit/moveit_core/robot_state/robot_state.hpp diff --git a/moveit_py/src/moveit/moveit_core/robot_trajectory/robot_trajectory.h b/moveit_py/src/moveit/moveit_core/robot_trajectory/robot_trajectory.hpp similarity index 100% rename from moveit_py/src/moveit/moveit_core/robot_trajectory/robot_trajectory.h rename to moveit_py/src/moveit/moveit_core/robot_trajectory/robot_trajectory.hpp diff --git a/moveit_py/src/moveit/moveit_core/transforms/transforms.h b/moveit_py/src/moveit/moveit_core/transforms/transforms.hpp similarity index 100% rename from moveit_py/src/moveit/moveit_core/transforms/transforms.h rename to moveit_py/src/moveit/moveit_core/transforms/transforms.hpp diff --git a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.hpp similarity index 100% rename from moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h rename to moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.hpp diff --git a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.hpp similarity index 100% rename from moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h rename to moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.hpp diff --git a/moveit_py/src/moveit/moveit_ros/moveit_cpp/moveit_cpp.h b/moveit_py/src/moveit/moveit_ros/moveit_cpp/moveit_cpp.hpp similarity index 100% rename from moveit_py/src/moveit/moveit_ros/moveit_cpp/moveit_cpp.h rename to moveit_py/src/moveit/moveit_ros/moveit_cpp/moveit_cpp.hpp diff --git a/moveit_py/src/moveit/moveit_ros/moveit_cpp/planning_component.h b/moveit_py/src/moveit/moveit_ros/moveit_cpp/planning_component.hpp similarity index 100% rename from moveit_py/src/moveit/moveit_ros/moveit_cpp/planning_component.h rename to moveit_py/src/moveit/moveit_ros/moveit_cpp/planning_component.hpp diff --git a/moveit_py/src/moveit/moveit_ros/planning_scene_monitor/planning_scene_monitor.h b/moveit_py/src/moveit/moveit_ros/planning_scene_monitor/planning_scene_monitor.hpp similarity index 100% rename from moveit_py/src/moveit/moveit_ros/planning_scene_monitor/planning_scene_monitor.h rename to moveit_py/src/moveit/moveit_ros/planning_scene_monitor/planning_scene_monitor.hpp diff --git a/moveit_py/src/moveit/moveit_ros/trajectory_execution_manager/trajectory_execution_manager.h b/moveit_py/src/moveit/moveit_ros/trajectory_execution_manager/trajectory_execution_manager.hpp similarity index 100% rename from moveit_py/src/moveit/moveit_ros/trajectory_execution_manager/trajectory_execution_manager.h rename to moveit_py/src/moveit/moveit_ros/trajectory_execution_manager/trajectory_execution_manager.hpp diff --git a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.hpp similarity index 100% rename from moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h rename to moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.hpp diff --git a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.hpp similarity index 100% rename from moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h rename to moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.hpp diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.hpp similarity index 100% rename from moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h rename to moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.hpp diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.hpp similarity index 100% rename from moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h rename to moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.hpp diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h b/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.hpp similarity index 100% rename from moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h rename to moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.hpp diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.hpp similarity index 100% rename from moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h rename to moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.hpp diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.hpp similarity index 100% rename from moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h rename to moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.hpp diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.hpp similarity index 100% rename from moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h rename to moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.hpp diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.hpp similarity index 100% rename from moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h rename to moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.hpp diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.hpp similarity index 100% rename from moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h rename to moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.hpp diff --git a/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h b/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.hpp similarity index 100% rename from moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h rename to moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.hpp diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.hpp similarity index 100% rename from moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h rename to moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.hpp diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.hpp similarity index 100% rename from moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h rename to moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.hpp diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.hpp similarity index 100% rename from moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h rename to moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.hpp diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.hpp similarity index 100% rename from moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h rename to moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.hpp diff --git a/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h b/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.hpp similarity index 100% rename from moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h rename to moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.hpp diff --git a/moveit_ros/move_group/include/moveit/move_group/capability_names.h b/moveit_ros/move_group/include/moveit/move_group/capability_names.hpp similarity index 100% rename from moveit_ros/move_group/include/moveit/move_group/capability_names.h rename to moveit_ros/move_group/include/moveit/move_group/capability_names.hpp diff --git a/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h b/moveit_ros/move_group/include/moveit/move_group/move_group_capability.hpp similarity index 100% rename from moveit_ros/move_group/include/moveit/move_group/move_group_capability.h rename to moveit_ros/move_group/include/moveit/move_group/move_group_capability.hpp diff --git a/moveit_ros/move_group/include/moveit/move_group/move_group_context.h b/moveit_ros/move_group/include/moveit/move_group/move_group_context.hpp similarity index 100% rename from moveit_ros/move_group/include/moveit/move_group/move_group_context.h rename to moveit_ros/move_group/include/moveit/move_group/move_group_context.hpp diff --git a/moveit_ros/move_group/src/default_capabilities/apply_planning_scene_service_capability.h b/moveit_ros/move_group/src/default_capabilities/apply_planning_scene_service_capability.hpp similarity index 100% rename from moveit_ros/move_group/src/default_capabilities/apply_planning_scene_service_capability.h rename to moveit_ros/move_group/src/default_capabilities/apply_planning_scene_service_capability.hpp diff --git a/moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.h b/moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.hpp similarity index 100% rename from moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.h rename to moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.hpp diff --git a/moveit_ros/move_group/src/default_capabilities/clear_octomap_service_capability.h b/moveit_ros/move_group/src/default_capabilities/clear_octomap_service_capability.hpp similarity index 100% rename from moveit_ros/move_group/src/default_capabilities/clear_octomap_service_capability.h rename to moveit_ros/move_group/src/default_capabilities/clear_octomap_service_capability.hpp diff --git a/moveit_ros/move_group/src/default_capabilities/execute_trajectory_action_capability.h b/moveit_ros/move_group/src/default_capabilities/execute_trajectory_action_capability.hpp similarity index 100% rename from moveit_ros/move_group/src/default_capabilities/execute_trajectory_action_capability.h rename to moveit_ros/move_group/src/default_capabilities/execute_trajectory_action_capability.hpp diff --git a/moveit_ros/move_group/src/default_capabilities/get_group_urdf_capability.h b/moveit_ros/move_group/src/default_capabilities/get_group_urdf_capability.hpp similarity index 100% rename from moveit_ros/move_group/src/default_capabilities/get_group_urdf_capability.h rename to moveit_ros/move_group/src/default_capabilities/get_group_urdf_capability.hpp diff --git a/moveit_ros/move_group/src/default_capabilities/get_planning_scene_service_capability.h b/moveit_ros/move_group/src/default_capabilities/get_planning_scene_service_capability.hpp similarity index 100% rename from moveit_ros/move_group/src/default_capabilities/get_planning_scene_service_capability.h rename to moveit_ros/move_group/src/default_capabilities/get_planning_scene_service_capability.hpp diff --git a/moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.h b/moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.hpp similarity index 100% rename from moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.h rename to moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.hpp diff --git a/moveit_ros/move_group/src/default_capabilities/load_geometry_from_file_service_capability.h b/moveit_ros/move_group/src/default_capabilities/load_geometry_from_file_service_capability.hpp similarity index 100% rename from moveit_ros/move_group/src/default_capabilities/load_geometry_from_file_service_capability.h rename to moveit_ros/move_group/src/default_capabilities/load_geometry_from_file_service_capability.hpp diff --git a/moveit_ros/move_group/src/default_capabilities/move_action_capability.h b/moveit_ros/move_group/src/default_capabilities/move_action_capability.hpp similarity index 100% rename from moveit_ros/move_group/src/default_capabilities/move_action_capability.h rename to moveit_ros/move_group/src/default_capabilities/move_action_capability.hpp diff --git a/moveit_ros/move_group/src/default_capabilities/plan_service_capability.h b/moveit_ros/move_group/src/default_capabilities/plan_service_capability.hpp similarity index 100% rename from moveit_ros/move_group/src/default_capabilities/plan_service_capability.h rename to moveit_ros/move_group/src/default_capabilities/plan_service_capability.hpp diff --git a/moveit_ros/move_group/src/default_capabilities/query_planners_service_capability.h b/moveit_ros/move_group/src/default_capabilities/query_planners_service_capability.hpp similarity index 100% rename from moveit_ros/move_group/src/default_capabilities/query_planners_service_capability.h rename to moveit_ros/move_group/src/default_capabilities/query_planners_service_capability.hpp diff --git a/moveit_ros/move_group/src/default_capabilities/save_geometry_to_file_service_capability.h b/moveit_ros/move_group/src/default_capabilities/save_geometry_to_file_service_capability.hpp similarity index 100% rename from moveit_ros/move_group/src/default_capabilities/save_geometry_to_file_service_capability.h rename to moveit_ros/move_group/src/default_capabilities/save_geometry_to_file_service_capability.hpp diff --git a/moveit_ros/move_group/src/default_capabilities/state_validation_service_capability.h b/moveit_ros/move_group/src/default_capabilities/state_validation_service_capability.hpp similarity index 100% rename from moveit_ros/move_group/src/default_capabilities/state_validation_service_capability.h rename to moveit_ros/move_group/src/default_capabilities/state_validation_service_capability.hpp diff --git a/moveit_ros/move_group/src/default_capabilities/tf_publisher_capability.h b/moveit_ros/move_group/src/default_capabilities/tf_publisher_capability.hpp similarity index 100% rename from moveit_ros/move_group/src/default_capabilities/tf_publisher_capability.h rename to moveit_ros/move_group/src/default_capabilities/tf_publisher_capability.hpp diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.hpp similarity index 100% rename from moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h rename to moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.hpp diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.hpp similarity index 100% rename from moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h rename to moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.hpp diff --git a/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h b/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.hpp similarity index 100% rename from moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h rename to moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.hpp diff --git a/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h b/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.hpp similarity index 100% rename from moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h rename to moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.hpp diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.hpp similarity index 100% rename from moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h rename to moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.hpp diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.hpp similarity index 100% rename from moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h rename to moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.hpp diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.hpp similarity index 100% rename from moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h rename to moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.hpp diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.hpp similarity index 100% rename from moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h rename to moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.hpp diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.hpp similarity index 100% rename from moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h rename to moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.hpp diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.hpp similarity index 100% rename from moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h rename to moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.hpp diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.hpp similarity index 100% rename from moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h rename to moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.hpp diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.hpp similarity index 100% rename from moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h rename to moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.hpp diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.hpp similarity index 100% rename from moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h rename to moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.hpp diff --git a/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h b/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.hpp similarity index 100% rename from moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h rename to moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.hpp diff --git a/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h b/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.hpp similarity index 100% rename from moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h rename to moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.hpp diff --git a/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.hpp similarity index 100% rename from moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h rename to moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.hpp diff --git a/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h b/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.hpp similarity index 100% rename from moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h rename to moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.hpp diff --git a/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h b/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.hpp similarity index 100% rename from moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h rename to moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.hpp diff --git a/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h b/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.hpp similarity index 100% rename from moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h rename to moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.hpp diff --git a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.hpp similarity index 100% rename from moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h rename to moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.hpp diff --git a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.hpp similarity index 100% rename from moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h rename to moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.hpp diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.hpp similarity index 100% rename from moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h rename to moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.hpp diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.hpp similarity index 100% rename from moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h rename to moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.hpp diff --git a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.hpp similarity index 100% rename from moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h rename to moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.hpp diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.hpp similarity index 100% rename from moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h rename to moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.hpp diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.hpp similarity index 100% rename from moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h rename to moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.hpp diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.hpp similarity index 100% rename from moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h rename to moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.hpp diff --git a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.hpp similarity index 100% rename from moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h rename to moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.hpp diff --git a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.hpp similarity index 100% rename from moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h rename to moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.hpp diff --git a/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h b/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.hpp similarity index 100% rename from moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h rename to moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.hpp diff --git a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.hpp similarity index 100% rename from moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h rename to moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.hpp diff --git a/moveit_ros/planning/trajectory_execution_manager/test/test_moveit_controller_manager.h b/moveit_ros/planning/trajectory_execution_manager/test/test_moveit_controller_manager.hpp similarity index 100% rename from moveit_ros/planning/trajectory_execution_manager/test/test_moveit_controller_manager.h rename to moveit_ros/planning/trajectory_execution_manager/test/test_moveit_controller_manager.hpp diff --git a/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h b/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.hpp similarity index 100% rename from moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h rename to moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.hpp diff --git a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.hpp similarity index 100% rename from moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h rename to moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.hpp diff --git a/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h b/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.hpp similarity index 100% rename from moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h rename to moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.hpp diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.hpp similarity index 100% rename from moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h rename to moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.hpp diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.hpp similarity index 100% rename from moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h rename to moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.hpp diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.hpp similarity index 100% rename from moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h rename to moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.hpp diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.hpp similarity index 100% rename from moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h rename to moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.hpp diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.hpp similarity index 100% rename from moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h rename to moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.hpp diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.hpp similarity index 100% rename from moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h rename to moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.hpp diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.hpp similarity index 100% rename from moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h rename to moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.hpp diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.hpp similarity index 100% rename from moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h rename to moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.hpp diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.hpp similarity index 100% rename from moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h rename to moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.hpp diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.hpp similarity index 100% rename from moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h rename to moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.hpp diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.hpp similarity index 100% rename from moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h rename to moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.hpp diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.hpp similarity index 100% rename from moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h rename to moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.hpp diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.hpp similarity index 100% rename from moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h rename to moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.hpp diff --git a/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h b/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.hpp similarity index 100% rename from moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h rename to moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.hpp diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.hpp similarity index 100% rename from moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h rename to moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.hpp diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.hpp similarity index 100% rename from moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h rename to moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.hpp diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.hpp similarity index 100% rename from moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h rename to moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.hpp diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.hpp similarity index 100% rename from moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h rename to moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.hpp diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.hpp similarity index 100% rename from moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h rename to moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.hpp diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.hpp similarity index 100% rename from moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h rename to moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.hpp diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.hpp similarity index 100% rename from moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h rename to moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.hpp diff --git a/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h b/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.hpp similarity index 100% rename from moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h rename to moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.hpp diff --git a/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.hpp similarity index 100% rename from moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h rename to moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.hpp diff --git a/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.hpp similarity index 100% rename from moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h rename to moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.hpp diff --git a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.hpp similarity index 100% rename from moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h rename to moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.hpp diff --git a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.hpp similarity index 100% rename from moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h rename to moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.hpp diff --git a/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/state_storage.hpp similarity index 100% rename from moveit_ros/warehouse/include/moveit/warehouse/state_storage.h rename to moveit_ros/warehouse/include/moveit/warehouse/state_storage.hpp diff --git a/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.hpp similarity index 100% rename from moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h rename to moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.hpp diff --git a/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h b/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.hpp similarity index 100% rename from moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h rename to moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.hpp From 252e5daee556adb0d71f473c74ff8b2e43cefadb Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Sun, 17 Nov 2024 17:20:37 +0000 Subject: [PATCH 04/53] Fixes moveit_core compiler errors --- .../allvalid/collision_detector_allocator_allvalid.hpp | 2 +- .../collision_detection/test_collision_common_panda.hpp | 4 ++-- .../moveit/collision_detection/test_collision_common_pr2.hpp | 2 +- moveit_core/collision_detection/src/world.cpp | 2 +- .../collision_detector_allocator_bullet.hpp | 2 +- .../collision_detector_allocator_fcl.hpp | 2 +- .../collision_detector_allocator_hybrid.hpp | 2 +- .../constraint_samplers/test/test_constraint_samplers.cpp | 2 +- .../include/moveit/kinematics_base/kinematics_base.hpp | 2 +- .../moveit/online_signal_smoothing/smoothing_base_class.hpp | 2 +- .../include/moveit/planning_scene/planning_scene.hpp | 2 +- .../include/moveit/mesh_filter/stereo_camera_model.hpp | 2 +- .../include/moveit/planning_pipeline/planning_pipeline.hpp | 2 +- .../moveit/planning_scene_monitor/planning_scene_monitor.hpp | 2 +- .../trajectory_execution_manager.hpp | 2 +- .../moveit/move_group_interface/move_group_interface.hpp | 2 +- .../moveit/robot_interaction/kinematic_options_map.hpp | 2 +- .../planning_scene_rviz_plugin/planning_scene_display.hpp | 2 +- .../include/moveit/warehouse/constraints_storage.hpp | 2 +- .../include/moveit/warehouse/planning_scene_storage.hpp | 2 +- .../warehouse/include/moveit/warehouse/state_storage.hpp | 2 +- 21 files changed, 22 insertions(+), 22 deletions(-) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.hpp b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.hpp index ccb95c0269..e0c2013d43 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.hpp +++ b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.hpp @@ -39,7 +39,7 @@ #include #include -#include +#include namespace collision_detection { diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.hpp b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.hpp index 6fb1a5e934..37fda1c204 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.hpp +++ b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.hpp @@ -41,8 +41,8 @@ #include #include -#include -#include +#include +#include #include #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.hpp b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.hpp index 5b7c668dff..ec5aabb0da 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.hpp +++ b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.hpp @@ -40,7 +40,7 @@ #include #include #include -#include +#include #include #include diff --git a/moveit_core/collision_detection/src/world.cpp b/moveit_core/collision_detection/src/world.cpp index 57e7315a40..b2262f93d5 100644 --- a/moveit_core/collision_detection/src/world.cpp +++ b/moveit_core/collision_detection/src/world.cpp @@ -35,7 +35,7 @@ /* Author: Acorn Pooley, Ioan Sucan */ #include -#include +#include #include #include #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.hpp b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.hpp index c703727022..50b533030a 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.hpp +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.hpp @@ -39,7 +39,7 @@ #include #include -#include +#include namespace collision_detection { diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.hpp b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.hpp index 855ab66b46..b7a2bce548 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.hpp +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.hpp @@ -39,7 +39,7 @@ #include #include -#include +#include namespace collision_detection { diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.hpp b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.hpp index 03a3c70a2a..a64c5b7fbb 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.hpp +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.hpp @@ -39,7 +39,7 @@ #include #include -#include +#include namespace collision_detection { diff --git a/moveit_core/constraint_samplers/test/test_constraint_samplers.cpp b/moveit_core/constraint_samplers/test/test_constraint_samplers.cpp index b977f7add6..15aa8581b4 100644 --- a/moveit_core/constraint_samplers/test/test_constraint_samplers.cpp +++ b/moveit_core/constraint_samplers/test/test_constraint_samplers.cpp @@ -43,7 +43,7 @@ #include #include -#include +#include #include #include diff --git a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.hpp b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.hpp index 7c8e97f7bb..4f674dd9fc 100644 --- a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.hpp +++ b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.hpp @@ -45,7 +45,7 @@ #include #include -#include +#include namespace moveit { diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.hpp b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.hpp index 4a46dbe063..dd35d00519 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.hpp +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.hpp @@ -41,7 +41,7 @@ #include #include -#include +#include #include diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.hpp b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.hpp index 5522293624..7141900012 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.hpp +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.hpp @@ -59,7 +59,7 @@ #include #include -#include +#include /** \brief This namespace includes the central class for representing planning contexts */ namespace planning_scene diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.hpp b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.hpp index db5ac3d289..cea79d81e7 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.hpp +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.hpp @@ -39,7 +39,7 @@ #include #include -#include +#include namespace mesh_filter { diff --git a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.hpp b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.hpp index 6ba0029d9c..18abda399b 100644 --- a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.hpp +++ b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.hpp @@ -48,7 +48,7 @@ #include #include #include -#include +#include #include namespace planning_pipeline diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.hpp b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.hpp index 434c81a43e..b634928369 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.hpp +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.hpp @@ -52,7 +52,7 @@ #include #include -#include +#include namespace planning_scene_monitor { diff --git a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.hpp b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.hpp index bcc394fc1a..b305371d54 100644 --- a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.hpp +++ b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.hpp @@ -50,7 +50,7 @@ #include #include -#include +#include namespace trajectory_execution_manager { diff --git a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.hpp b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.hpp index bd6c4bb978..7692dc4f6a 100644 --- a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.hpp +++ b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.hpp @@ -58,7 +58,7 @@ #include #include -#include +#include namespace moveit { diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.hpp b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.hpp index 5ffb947fba..4c167bb00a 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.hpp +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.hpp @@ -40,7 +40,7 @@ #include #include -#include +#include namespace robot_interaction { diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.hpp b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.hpp index e2bfd706ee..1c0aa57c77 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.hpp +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.hpp @@ -47,7 +47,7 @@ #include #endif -#include +#include namespace Ogre { diff --git a/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.hpp b/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.hpp index 3d99f27759..44558f5c12 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.hpp +++ b/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.hpp @@ -40,7 +40,7 @@ #include #include -#include +#include #include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.hpp b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.hpp index 47806c1986..11468defd3 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.hpp +++ b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.hpp @@ -43,7 +43,7 @@ #include #include -#include +#include namespace moveit_warehouse { diff --git a/moveit_ros/warehouse/include/moveit/warehouse/state_storage.hpp b/moveit_ros/warehouse/include/moveit/warehouse/state_storage.hpp index 7efe94d366..d8b0d1d03c 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/state_storage.hpp +++ b/moveit_ros/warehouse/include/moveit/warehouse/state_storage.hpp @@ -41,7 +41,7 @@ #include #include -#include +#include namespace moveit_warehouse { From c4ebfc5898cd9e00c54af9857a849da77a74dd6b Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Sun, 17 Nov 2024 17:54:48 +0000 Subject: [PATCH 05/53] Fixes compilation up to moveit_planners --- .../include/chomp_interface/chomp_interface.hpp | 4 ++-- .../include/chomp_motion_planner/chomp_cost.hpp | 2 +- .../include/chomp_motion_planner/chomp_optimizer.hpp | 8 ++++---- .../include/chomp_motion_planner/chomp_planner.hpp | 2 +- .../include/chomp_motion_planner/chomp_trajectory.hpp | 2 +- .../chomp/chomp_motion_planner/src/chomp_cost.cpp | 4 ++-- .../chomp/chomp_motion_planner/src/chomp_optimizer.cpp | 4 ++-- .../chomp/chomp_motion_planner/src/chomp_parameters.cpp | 2 +- .../chomp/chomp_motion_planner/src/chomp_planner.cpp | 6 +++--- .../chomp/chomp_motion_planner/src/chomp_trajectory.cpp | 2 +- .../moveit/ompl_interface/detail/constraints_library.hpp | 2 +- .../trajectory_generator_ptp.hpp | 2 +- .../src/default_capabilities/tf_publisher_capability.cpp | 2 +- 13 files changed, 21 insertions(+), 21 deletions(-) diff --git a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.hpp b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.hpp index 1b11f6396d..d00462fffa 100644 --- a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.hpp +++ b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.hpp @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include #include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.hpp b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.hpp index 086b352f0a..f0abfc365d 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.hpp +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.hpp @@ -36,7 +36,7 @@ #pragma once -#include +#include #include #include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.hpp b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.hpp index c6c8fc1f52..f0025808d1 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.hpp +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.hpp @@ -36,10 +36,10 @@ #pragma once -#include -#include -#include -#include +#include +#include +#include +#include #include #include #include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.hpp b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.hpp index 8559261e16..fd107fa7e6 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.hpp +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.hpp @@ -36,7 +36,7 @@ #pragma once -#include +#include #include #include #include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.hpp b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.hpp index 904db57d9d..08d63b1a92 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.hpp +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.hpp @@ -36,7 +36,7 @@ #pragma once -#include +#include #include #include diff --git a/moveit_planners/chomp/chomp_motion_planner/src/chomp_cost.cpp b/moveit_planners/chomp/chomp_motion_planner/src/chomp_cost.cpp index ebe8ad2cd1..5b0e5341c7 100644 --- a/moveit_planners/chomp/chomp_motion_planner/src/chomp_cost.cpp +++ b/moveit_planners/chomp/chomp_motion_planner/src/chomp_cost.cpp @@ -34,8 +34,8 @@ /* Author: Mrinal Kalakrishnan */ -#include -#include +#include +#include #include diff --git a/moveit_planners/chomp/chomp_motion_planner/src/chomp_optimizer.cpp b/moveit_planners/chomp/chomp_motion_planner/src/chomp_optimizer.cpp index a83a1e1427..250d8f6ffd 100644 --- a/moveit_planners/chomp/chomp_motion_planner/src/chomp_optimizer.cpp +++ b/moveit_planners/chomp/chomp_motion_planner/src/chomp_optimizer.cpp @@ -34,8 +34,8 @@ /* Author: Mrinal Kalakrishnan */ -#include -#include +#include +#include #include #include #include diff --git a/moveit_planners/chomp/chomp_motion_planner/src/chomp_parameters.cpp b/moveit_planners/chomp/chomp_motion_planner/src/chomp_parameters.cpp index 58dc3aa2eb..3a45a47e5d 100644 --- a/moveit_planners/chomp/chomp_motion_planner/src/chomp_parameters.cpp +++ b/moveit_planners/chomp/chomp_motion_planner/src/chomp_parameters.cpp @@ -34,7 +34,7 @@ /* Author: Mrinal Kalakrishnan */ -#include +#include #include diff --git a/moveit_planners/chomp/chomp_motion_planner/src/chomp_planner.cpp b/moveit_planners/chomp/chomp_motion_planner/src/chomp_planner.cpp index d0c82f05c3..24ffe990b2 100644 --- a/moveit_planners/chomp/chomp_motion_planner/src/chomp_planner.cpp +++ b/moveit_planners/chomp/chomp_motion_planner/src/chomp_planner.cpp @@ -34,9 +34,9 @@ /* Author: E. Gil Jones */ -#include -#include -#include +#include +#include +#include #include #include #include diff --git a/moveit_planners/chomp/chomp_motion_planner/src/chomp_trajectory.cpp b/moveit_planners/chomp/chomp_motion_planner/src/chomp_trajectory.cpp index c0dc2abe53..c22618930f 100644 --- a/moveit_planners/chomp/chomp_motion_planner/src/chomp_trajectory.cpp +++ b/moveit_planners/chomp/chomp_motion_planner/src/chomp_trajectory.cpp @@ -34,7 +34,7 @@ /* Author: Mrinal Kalakrishnan */ -#include +#include namespace chomp { diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.hpp b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.hpp index 9f783ac0bf..7f831e6354 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.hpp +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.hpp @@ -40,7 +40,7 @@ #include #include #include -#include +#include #include namespace ompl_interface diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.hpp b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.hpp index e57b128c60..f4514c123f 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.hpp +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.hpp @@ -37,7 +37,7 @@ #include #include -#include +#include #include #include diff --git a/moveit_ros/move_group/src/default_capabilities/tf_publisher_capability.cpp b/moveit_ros/move_group/src/default_capabilities/tf_publisher_capability.cpp index 4f6f378a05..f6035e52ca 100644 --- a/moveit_ros/move_group/src/default_capabilities/tf_publisher_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/tf_publisher_capability.cpp @@ -38,7 +38,7 @@ #include #include #include -#include +#include #include #include #include From f64a9fa74ada473675931a01b4989366cb4c8662 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Sun, 17 Nov 2024 18:01:54 +0000 Subject: [PATCH 06/53] Fixes compilation up to moveit_py --- .../benchmarks/include/moveit/benchmarks/BenchmarkExecutor.hpp | 2 +- .../include/moveit/warehouse/moveit_message_storage.hpp | 2 +- moveit_ros/warehouse/src/moveit_message_storage.cpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.hpp b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.hpp index 213fc629a3..e23c686e18 100644 --- a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.hpp +++ b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.hpp @@ -46,7 +46,7 @@ #include #include #include -#include +#include #include #include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.hpp b/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.hpp index f672c5ec84..dd73ffa285 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.hpp +++ b/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.hpp @@ -36,7 +36,7 @@ #pragma once -#include +#include #include #include diff --git a/moveit_ros/warehouse/src/moveit_message_storage.cpp b/moveit_ros/warehouse/src/moveit_message_storage.cpp index 127054c604..d50c91b795 100644 --- a/moveit_ros/warehouse/src/moveit_message_storage.cpp +++ b/moveit_ros/warehouse/src/moveit_message_storage.cpp @@ -35,7 +35,7 @@ /* Author: Ioan Sucan */ #include -#include +#include #include #include #include From 603ba8694a6d6ec88c1a333450a1c82d385fc6ac Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Sun, 17 Nov 2024 18:17:37 +0000 Subject: [PATCH 07/53] Fixes compilation up to moveit_ros --- .../motion_planning_rviz_plugin/CMakeLists.txt | 10 +++++----- .../src/motion_planning_display.cpp | 2 +- .../src/motion_planning_frame.cpp | 2 +- .../src/motion_planning_frame_context.cpp | 2 +- .../src/motion_planning_frame_joints_widget.cpp | 2 +- .../src/motion_planning_frame_manipulation.cpp | 2 +- .../src/motion_planning_frame_objects.cpp | 2 +- .../src/motion_planning_frame_planning.cpp | 2 +- .../src/motion_planning_frame_scenes.cpp | 2 +- .../src/motion_planning_frame_states.cpp | 2 +- .../src/ui/motion_planning_rviz_plugin_frame.ui | 2 +- .../planning_scene_rviz_plugin/CMakeLists.txt | 2 +- .../robot_state_rviz_plugin/CMakeLists.txt | 2 +- .../rviz_plugin_render_tools/CMakeLists.txt | 14 +++++++------- .../trajectory_rviz_plugin/CMakeLists.txt | 2 +- 15 files changed, 25 insertions(+), 25 deletions(-) diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/CMakeLists.txt b/moveit_ros/visualization/motion_planning_rviz_plugin/CMakeLists.txt index dc4f94ac8f..711211c89f 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/CMakeLists.txt +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/CMakeLists.txt @@ -1,9 +1,9 @@ set(HEADERS - include/moveit/motion_planning_rviz_plugin/motion_planning_display.h - include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h - include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h - include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h - include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h) + include/moveit/motion_planning_rviz_plugin/motion_planning_display.hpp + include/moveit/motion_planning_rviz_plugin/motion_planning_frame.hpp + include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.hpp + include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.hpp + include/moveit/motion_planning_rviz_plugin/interactive_marker_display.hpp) qt5_wrap_ui(UIC_FILES src/ui/motion_planning_rviz_plugin_frame.ui src/ui/motion_planning_rviz_plugin_frame_joints.ui) diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp index fd22e4406e..1880c59b3a 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp @@ -67,7 +67,7 @@ #include -#include "ui_motion_planning_rviz_plugin_frame.hpp" +#include "ui_motion_planning_rviz_plugin_frame.h" #include #include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame.cpp index 22590f8591..074545f324 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame.cpp @@ -57,7 +57,7 @@ #include #include -#include "ui_motion_planning_rviz_plugin_frame.hpp" +#include "ui_motion_planning_rviz_plugin_frame.h" namespace moveit_rviz_plugin { diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_context.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_context.cpp index de8b9d0516..13aa519ac6 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_context.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_context.cpp @@ -45,7 +45,7 @@ #include #include -#include "ui_motion_planning_rviz_plugin_frame.hpp" +#include "ui_motion_planning_rviz_plugin_frame.h" namespace moveit_rviz_plugin { diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_joints_widget.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_joints_widget.cpp index a649c7f86c..39de464182 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_joints_widget.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_joints_widget.cpp @@ -37,7 +37,7 @@ #include #include -#include "ui_motion_planning_rviz_plugin_frame_joints.hpp" +#include "ui_motion_planning_rviz_plugin_frame_joints.h" #include #include #include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_manipulation.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_manipulation.cpp index 808c7daa64..57ef02b94f 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_manipulation.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_manipulation.cpp @@ -43,7 +43,7 @@ #include -#include "ui_motion_planning_rviz_plugin_frame.hpp" +#include "ui_motion_planning_rviz_plugin_frame.h" namespace moveit_rviz_plugin { diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_objects.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_objects.cpp index fdfa5e7bc5..f3faa13b3b 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_objects.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_objects.cpp @@ -53,7 +53,7 @@ #include #include -#include "ui_motion_planning_rviz_plugin_frame.hpp" +#include "ui_motion_planning_rviz_plugin_frame.h" namespace { diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_planning.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_planning.cpp index 8bc632a558..115f32bc6a 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_planning.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_planning.cpp @@ -46,7 +46,7 @@ #include #include -#include "ui_motion_planning_rviz_plugin_frame.hpp" +#include "ui_motion_planning_rviz_plugin_frame.h" namespace moveit_rviz_plugin { diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_scenes.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_scenes.cpp index e5f99b4d51..bfb391b823 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_scenes.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_scenes.cpp @@ -51,7 +51,7 @@ #include #include -#include "ui_motion_planning_rviz_plugin_frame.hpp" +#include "ui_motion_planning_rviz_plugin_frame.h" #include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_states.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_states.cpp index 90f06b1519..1280f2e38a 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_states.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_states.cpp @@ -42,7 +42,7 @@ #include #include -#include "ui_motion_planning_rviz_plugin_frame.hpp" +#include "ui_motion_planning_rviz_plugin_frame.h" namespace moveit_rviz_plugin { diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/ui/motion_planning_rviz_plugin_frame.ui b/moveit_ros/visualization/motion_planning_rviz_plugin/src/ui/motion_planning_rviz_plugin_frame.ui index 346228701e..18fb7210bc 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/ui/motion_planning_rviz_plugin_frame.ui +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/ui/motion_planning_rviz_plugin_frame.ui @@ -2080,7 +2080,7 @@ This is usually achieved by random seeding, which can flip the robot configurati moveit_rviz_plugin::MotionPlanningParamWidget QTreeView -
moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h
+
moveit/motion_planning_rviz_plugin/motion_planning_param_widget.hpp
diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt b/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt index 71f84afb5d..efe2dc41f4 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt @@ -1,7 +1,7 @@ add_library( moveit_planning_scene_rviz_plugin_core SHARED src/planning_scene_display.cpp src/background_processing.cpp - include/moveit/planning_scene_rviz_plugin/planning_scene_display.h) + include/moveit/planning_scene_rviz_plugin/planning_scene_display.hpp) include(GenerateExportHeader) generate_export_header(moveit_planning_scene_rviz_plugin_core) target_include_directories( diff --git a/moveit_ros/visualization/robot_state_rviz_plugin/CMakeLists.txt b/moveit_ros/visualization/robot_state_rviz_plugin/CMakeLists.txt index 73b5751a1e..f9bd7f4c8b 100644 --- a/moveit_ros/visualization/robot_state_rviz_plugin/CMakeLists.txt +++ b/moveit_ros/visualization/robot_state_rviz_plugin/CMakeLists.txt @@ -1,7 +1,7 @@ add_library( moveit_robot_state_rviz_plugin_core SHARED src/robot_state_display.cpp - include/moveit/robot_state_rviz_plugin/robot_state_display.h) + include/moveit/robot_state_rviz_plugin/robot_state_display.hpp) set_target_properties(moveit_robot_state_rviz_plugin_core PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") target_link_libraries(moveit_robot_state_rviz_plugin_core diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/CMakeLists.txt b/moveit_ros/visualization/rviz_plugin_render_tools/CMakeLists.txt index 65d2ce41a4..2a8c81a4dd 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/CMakeLists.txt +++ b/moveit_ros/visualization/rviz_plugin_render_tools/CMakeLists.txt @@ -1,11 +1,11 @@ set(HEADERS - include/moveit/rviz_plugin_render_tools/octomap_render.h - include/moveit/rviz_plugin_render_tools/planning_link_updater.h - include/moveit/rviz_plugin_render_tools/planning_scene_render.h - include/moveit/rviz_plugin_render_tools/render_shapes.h - include/moveit/rviz_plugin_render_tools/robot_state_visualization.h - include/moveit/rviz_plugin_render_tools/trajectory_visualization.h - include/moveit/rviz_plugin_render_tools/trajectory_panel.h + include/moveit/rviz_plugin_render_tools/octomap_render.hpp + include/moveit/rviz_plugin_render_tools/planning_link_updater.hpp + include/moveit/rviz_plugin_render_tools/planning_scene_render.hpp + include/moveit/rviz_plugin_render_tools/render_shapes.hpp + include/moveit/rviz_plugin_render_tools/robot_state_visualization.hpp + include/moveit/rviz_plugin_render_tools/trajectory_visualization.hpp + include/moveit/rviz_plugin_render_tools/trajectory_panel.hpp include/ogre_helpers/mesh_shape.hpp) include_directories(${CMAKE_CURRENT_BINARY_DIR}) diff --git a/moveit_ros/visualization/trajectory_rviz_plugin/CMakeLists.txt b/moveit_ros/visualization/trajectory_rviz_plugin/CMakeLists.txt index 63cdcf6316..8a58e56eba 100644 --- a/moveit_ros/visualization/trajectory_rviz_plugin/CMakeLists.txt +++ b/moveit_ros/visualization/trajectory_rviz_plugin/CMakeLists.txt @@ -1,5 +1,5 @@ # Header files that need Qt Moc pre-processing for use with Qt signals, etc: -set(HEADERS include/moveit/trajectory_rviz_plugin/trajectory_display.h) +set(HEADERS include/moveit/trajectory_rviz_plugin/trajectory_display.hpp) include_directories(${CMAKE_CURRENT_BINARY_DIR}) From 3199c85461fea1232aa7dd13a787e7e30e14bc7e Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Sun, 17 Nov 2024 18:41:18 +0000 Subject: [PATCH 08/53] Updates MIGRATION.md --- MIGRATION.md | 1 + 1 file changed, 1 insertion(+) diff --git a/MIGRATION.md b/MIGRATION.md index 9af12e14c4..3f891bed5d 100644 --- a/MIGRATION.md +++ b/MIGRATION.md @@ -3,6 +3,7 @@ API changes in MoveIt releases ## ROS Rolling +- [11/2024] All MoveIt 2 headers have been updated to use the `.hpp` extension. Please update all imports from `.h` to `.hpp`. - [12/2023] `trajectory_processing::Path` and `trajectory_processing::Trajectory` APIs have been updated to prevent misuse. The constructors have been replaced by builder methods so that errors can be communicated. Paths and trajectories now need to be created with `Path::Create()` and `Trajectory::Create()`. These methods now return an `std::optional` that needs to be checked for a valid value. `Trajectory` no longer has the `isValid()` method. If it's invalid, `Trajectory::Create()` will return `std::nullopt`. Finally, `Path` now takes the list of input waypoints as `std::vector`, instead of `std::list`. - [12/2023] LMA kinematics plugin is removed to remove the maintenance work because better alternatives exist like KDL or TracIK From fc0425d1fc41ab89ea1422fe0f3becac18ede5a7 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Sun, 17 Nov 2024 18:55:33 +0000 Subject: [PATCH 09/53] Fixes chomp imports --- .../include/chomp_interface/chomp_planning_context.hpp | 2 +- moveit_planners/chomp/chomp_interface/src/chomp_interface.cpp | 2 +- .../chomp/chomp_interface/src/chomp_planning_context.cpp | 2 +- moveit_planners/chomp/chomp_interface/src/chomp_plugin.cpp | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.hpp b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.hpp index 540aa438df..dcb69871c6 100644 --- a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.hpp +++ b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.hpp @@ -36,7 +36,7 @@ #pragma once -#include +#include #include #include diff --git a/moveit_planners/chomp/chomp_interface/src/chomp_interface.cpp b/moveit_planners/chomp/chomp_interface/src/chomp_interface.cpp index f7cd00ad37..dd1446435d 100644 --- a/moveit_planners/chomp/chomp_interface/src/chomp_interface.cpp +++ b/moveit_planners/chomp/chomp_interface/src/chomp_interface.cpp @@ -34,7 +34,7 @@ /* Author: E. Gil Jones */ -#include +#include #include namespace chomp_interface diff --git a/moveit_planners/chomp/chomp_interface/src/chomp_planning_context.cpp b/moveit_planners/chomp/chomp_interface/src/chomp_planning_context.cpp index 122cc2c763..e24c953718 100644 --- a/moveit_planners/chomp/chomp_interface/src/chomp_planning_context.cpp +++ b/moveit_planners/chomp/chomp_interface/src/chomp_planning_context.cpp @@ -34,7 +34,7 @@ /* Author: Chittaranjan Srinivas Swaminathan */ -#include +#include #include namespace chomp_interface diff --git a/moveit_planners/chomp/chomp_interface/src/chomp_plugin.cpp b/moveit_planners/chomp/chomp_interface/src/chomp_plugin.cpp index 64f8e7a6cf..569742c10d 100644 --- a/moveit_planners/chomp/chomp_interface/src/chomp_plugin.cpp +++ b/moveit_planners/chomp/chomp_interface/src/chomp_plugin.cpp @@ -32,7 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include #include #include #include From f0d1f216dd95560e5a460490831bda3c2672c6b5 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Sun, 17 Nov 2024 19:45:32 +0000 Subject: [PATCH 10/53] Fixes ikfast imports --- .../scripts/create_ikfast_moveit_plugin.py | 6 +++--- .../src/prbt_manipulator_ikfast_solver.cpp | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/moveit_kinematics/ikfast_kinematics_plugin/scripts/create_ikfast_moveit_plugin.py b/moveit_kinematics/ikfast_kinematics_plugin/scripts/create_ikfast_moveit_plugin.py index 06c2f103a2..45495eff73 100755 --- a/moveit_kinematics/ikfast_kinematics_plugin/scripts/create_ikfast_moveit_plugin.py +++ b/moveit_kinematics/ikfast_kinematics_plugin/scripts/create_ikfast_moveit_plugin.py @@ -251,7 +251,7 @@ def create_ikfast_package(args): def find_template_dir(): for candidate in [os.path.dirname(__file__) + "/../templates"]: - if os.path.exists(candidate) and os.path.exists(candidate + "/ikfast.hpp"): + if os.path.exists(candidate) and os.path.exists(candidate + "/ikfast.h"): return os.path.realpath(candidate) try: return os.path.join( @@ -303,8 +303,8 @@ def update_ikfast_package(args): # Copy ikfast header file copy_file( - template_dir + "/ikfast.hpp", - args.ikfast_plugin_pkg_path + "/include/ikfast.hpp", + template_dir + "/ikfast.h", + args.ikfast_plugin_pkg_path + "/include/ikfast.h", "ikfast header file", ) # Create ikfast plugin template diff --git a/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/src/prbt_manipulator_ikfast_solver.cpp b/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/src/prbt_manipulator_ikfast_solver.cpp index 207f1f12bb..8741aa7cce 100644 --- a/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/src/prbt_manipulator_ikfast_solver.cpp +++ b/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/src/prbt_manipulator_ikfast_solver.cpp @@ -22,7 +22,7 @@ /// To compile without any main function as a shared object (might need -llapack): /// gcc -fPIC -lstdc++ -DIKFAST_NO_MAIN -DIKFAST_CLIBRARY -shared -Wl,-soname,libik.so -o libik.so ik.cpp #define IKFAST_HAS_LIBRARY -#include "ikfast.hpp" // found inside share/openrave-X.Y/python/ikfast.h +#include "ikfast.h" // found inside share/openrave-X.Y/python/ikfast.h using namespace ikfast; // check if the included ikfast version matches what this file was compiled with From 294f8902d4c36ac6b3fa9ab959d347e3ea0c681f Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Sun, 17 Nov 2024 20:11:09 +0000 Subject: [PATCH 11/53] Adds create_deprecated_headers.py --- moveit/scripts/create_deprecated_headers.py | 52 +++++++++++++++++++++ 1 file changed, 52 insertions(+) create mode 100755 moveit/scripts/create_deprecated_headers.py diff --git a/moveit/scripts/create_deprecated_headers.py b/moveit/scripts/create_deprecated_headers.py new file mode 100755 index 0000000000..8042967f56 --- /dev/null +++ b/moveit/scripts/create_deprecated_headers.py @@ -0,0 +1,52 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- + +# Copyright 2021 PickNik Inc. +# +# 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 the PickNik Inc. 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 HOLDER 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. + +import sys +from pathlib import Path + +# TODO: This doesn't work for chomp and pilz +MOVEIT_HPPS = "**/moveit*/**/*.hpp" +USAGE = "Usage: ./generate_deprecated_headers " +DEPRECATION = "{0}.h imports are deprecated. Consider using {0}.hpp" + +def create_c_header(hpp_path: str) -> None: + header_directory = hpp_path.parent + file = hpp_path.name.replace(".hpp", "") + with open(header_directory/f"{file}.h", "w") as h_file: + h_file.write(f"#warning {DEPRECATION.format(file)}\n") + h_file.write(f"#include <{file}.hpp>\n") + +if __name__ == "__main__": + if len(sys.argv) != 2: + sys.exit(USAGE) + install_directory = sys.argv[1] + for hpp_path in Path(install_directory).rglob(MOVEIT_HPPS): + create_c_header(hpp_path) From be8f3fd5e3ae4edde161f5085a9879e119074592 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Sun, 17 Nov 2024 20:14:37 +0000 Subject: [PATCH 12/53] Fixes lingering version.h --- moveit_core/version/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/moveit_core/version/CMakeLists.txt b/moveit_core/version/CMakeLists.txt index f41c589a2d..96a8474221 100644 --- a/moveit_core/version/CMakeLists.txt +++ b/moveit_core/version/CMakeLists.txt @@ -13,7 +13,7 @@ message( # https://stackoverflow.com/questions/13920072/how-to-always-run-command-when-building-regardless-of-any-dependency add_custom_command( - OUTPUT ${CMAKE_BINARY_DIR}/include/moveit/version.h always_rebuild + OUTPUT ${CMAKE_BINARY_DIR}/include/moveit/version.hpp always_rebuild COMMENT "Generate version header" COMMAND ${CMAKE_COMMAND} -DVERSION_FILE_PATH="${CMAKE_BINARY_DIR}/include" From 4ae41eaf3fa913e187d92957959d6e2578702517 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Sun, 17 Nov 2024 20:17:41 +0000 Subject: [PATCH 13/53] Fixes python formatting --- moveit/scripts/create_deprecated_headers.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/moveit/scripts/create_deprecated_headers.py b/moveit/scripts/create_deprecated_headers.py index 8042967f56..d18fe8a50b 100755 --- a/moveit/scripts/create_deprecated_headers.py +++ b/moveit/scripts/create_deprecated_headers.py @@ -37,13 +37,15 @@ USAGE = "Usage: ./generate_deprecated_headers " DEPRECATION = "{0}.h imports are deprecated. Consider using {0}.hpp" + def create_c_header(hpp_path: str) -> None: header_directory = hpp_path.parent file = hpp_path.name.replace(".hpp", "") - with open(header_directory/f"{file}.h", "w") as h_file: + with open(header_directory / f"{file}.h", "w") as h_file: h_file.write(f"#warning {DEPRECATION.format(file)}\n") h_file.write(f"#include <{file}.hpp>\n") + if __name__ == "__main__": if len(sys.argv) != 2: sys.exit(USAGE) From 5a2843c78879a26c5ae16385c5ab150382775cb4 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Sun, 17 Nov 2024 20:20:46 +0000 Subject: [PATCH 14/53] Updates MIGRATION.md --- MIGRATION.md | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/MIGRATION.md b/MIGRATION.md index 3f891bed5d..b24cbcba8c 100644 --- a/MIGRATION.md +++ b/MIGRATION.md @@ -3,7 +3,9 @@ API changes in MoveIt releases ## ROS Rolling -- [11/2024] All MoveIt 2 headers have been updated to use the `.hpp` extension. Please update all imports from `.h` to `.hpp`. +- [11/2024] All MoveIt 2 headers have been updated to use the `.hpp` extension. +`.h` headers are now autogenerated with a deprecation warning, and may be removed in future releases. +Please update your imports to use the `.hpp` headers. - [12/2023] `trajectory_processing::Path` and `trajectory_processing::Trajectory` APIs have been updated to prevent misuse. The constructors have been replaced by builder methods so that errors can be communicated. Paths and trajectories now need to be created with `Path::Create()` and `Trajectory::Create()`. These methods now return an `std::optional` that needs to be checked for a valid value. `Trajectory` no longer has the `isValid()` method. If it's invalid, `Trajectory::Create()` will return `std::nullopt`. Finally, `Path` now takes the list of input waypoints as `std::vector`, instead of `std::list`. - [12/2023] LMA kinematics plugin is removed to remove the maintenance work because better alternatives exist like KDL or TracIK From 84a6ab06acb56a10f83ec9e87b1505a9ff16c610 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Sun, 17 Nov 2024 20:25:06 +0000 Subject: [PATCH 15/53] Fixes MIGRATION.md formatting --- MIGRATION.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/MIGRATION.md b/MIGRATION.md index b24cbcba8c..e6ba8a8d6c 100644 --- a/MIGRATION.md +++ b/MIGRATION.md @@ -3,7 +3,7 @@ API changes in MoveIt releases ## ROS Rolling -- [11/2024] All MoveIt 2 headers have been updated to use the `.hpp` extension. +- [11/2024] All MoveIt 2 headers have been updated to use the `.hpp` extension. `.h` headers are now autogenerated with a deprecation warning, and may be removed in future releases. Please update your imports to use the `.hpp` headers. - [12/2023] `trajectory_processing::Path` and `trajectory_processing::Trajectory` APIs have been updated to prevent misuse. From 483f5b5f46f66fa33fdb6a71073c4c375c438334 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Sun, 17 Nov 2024 20:47:17 +0000 Subject: [PATCH 16/53] Fixes ikfast errors --- .../scripts/create_ikfast_moveit_plugin.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/moveit_kinematics/ikfast_kinematics_plugin/scripts/create_ikfast_moveit_plugin.py b/moveit_kinematics/ikfast_kinematics_plugin/scripts/create_ikfast_moveit_plugin.py index 45495eff73..06c2f103a2 100755 --- a/moveit_kinematics/ikfast_kinematics_plugin/scripts/create_ikfast_moveit_plugin.py +++ b/moveit_kinematics/ikfast_kinematics_plugin/scripts/create_ikfast_moveit_plugin.py @@ -251,7 +251,7 @@ def create_ikfast_package(args): def find_template_dir(): for candidate in [os.path.dirname(__file__) + "/../templates"]: - if os.path.exists(candidate) and os.path.exists(candidate + "/ikfast.h"): + if os.path.exists(candidate) and os.path.exists(candidate + "/ikfast.hpp"): return os.path.realpath(candidate) try: return os.path.join( @@ -303,8 +303,8 @@ def update_ikfast_package(args): # Copy ikfast header file copy_file( - template_dir + "/ikfast.h", - args.ikfast_plugin_pkg_path + "/include/ikfast.h", + template_dir + "/ikfast.hpp", + args.ikfast_plugin_pkg_path + "/include/ikfast.hpp", "ikfast header file", ) # Create ikfast plugin template From d0bb7e7c6951797ca4abec6e56112a45e93a61b4 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Sun, 17 Nov 2024 20:56:38 +0000 Subject: [PATCH 17/53] Fixes ikfast errors --- .../src/prbt_manipulator_ikfast_solver.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/src/prbt_manipulator_ikfast_solver.cpp b/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/src/prbt_manipulator_ikfast_solver.cpp index 8741aa7cce..870c0f8fea 100644 --- a/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/src/prbt_manipulator_ikfast_solver.cpp +++ b/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/src/prbt_manipulator_ikfast_solver.cpp @@ -22,11 +22,11 @@ /// To compile without any main function as a shared object (might need -llapack): /// gcc -fPIC -lstdc++ -DIKFAST_NO_MAIN -DIKFAST_CLIBRARY -shared -Wl,-soname,libik.so -o libik.so ik.cpp #define IKFAST_HAS_LIBRARY -#include "ikfast.h" // found inside share/openrave-X.Y/python/ikfast.h +#include "ikfast.hpp" // found inside share/openrave-X.Y/python/ikfast.hpp using namespace ikfast; // check if the included ikfast version matches what this file was compiled with -static_assert(IKFAST_VERSION==61); // version found in ikfast.h +static_assert(IKFAST_VERSION==61); // version found in ikfast.hpp #include #include From 194d544121e3349ca266409ea10407f0ecb580d6 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Sun, 17 Nov 2024 21:06:32 +0000 Subject: [PATCH 18/53] Fixes tf2_ros imports --- moveit_ros/moveit_servo/demos/cpp_interface/demo_pose.cpp | 2 +- moveit_ros/moveit_servo/demos/cpp_interface/demo_twist.cpp | 2 +- moveit_ros/moveit_servo/include/moveit_servo/servo.hpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/moveit_ros/moveit_servo/demos/cpp_interface/demo_pose.cpp b/moveit_ros/moveit_servo/demos/cpp_interface/demo_pose.cpp index 24e9bc33a3..4c713fd8b6 100644 --- a/moveit_ros/moveit_servo/demos/cpp_interface/demo_pose.cpp +++ b/moveit_ros/moveit_servo/demos/cpp_interface/demo_pose.cpp @@ -45,7 +45,7 @@ #include #include #include -#include +#include #include using namespace moveit_servo; diff --git a/moveit_ros/moveit_servo/demos/cpp_interface/demo_twist.cpp b/moveit_ros/moveit_servo/demos/cpp_interface/demo_twist.cpp index a73f319b3c..8c92fa4cfc 100644 --- a/moveit_ros/moveit_servo/demos/cpp_interface/demo_twist.cpp +++ b/moveit_ros/moveit_servo/demos/cpp_interface/demo_twist.cpp @@ -44,7 +44,7 @@ #include #include #include -#include +#include #include using namespace moveit_servo; diff --git a/moveit_ros/moveit_servo/include/moveit_servo/servo.hpp b/moveit_ros/moveit_servo/include/moveit_servo/servo.hpp index d4ec69e84a..d0331c650d 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/servo.hpp +++ b/moveit_ros/moveit_servo/include/moveit_servo/servo.hpp @@ -51,7 +51,7 @@ #include #include #include -#include +#include #include #include #include From 79247692bff299aa363c66ecae0e8d4c27700e4f Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Sun, 17 Nov 2024 21:24:28 +0000 Subject: [PATCH 19/53] Fixes ikfast errors --- .../scripts/create_ikfast_moveit_plugin.py | 6 +++--- .../templates/{ikfast.hpp => ikfast.h} | 0 .../src/prbt_manipulator_ikfast_solver.cpp | 4 ++-- 3 files changed, 5 insertions(+), 5 deletions(-) rename moveit_kinematics/ikfast_kinematics_plugin/templates/{ikfast.hpp => ikfast.h} (100%) diff --git a/moveit_kinematics/ikfast_kinematics_plugin/scripts/create_ikfast_moveit_plugin.py b/moveit_kinematics/ikfast_kinematics_plugin/scripts/create_ikfast_moveit_plugin.py index 06c2f103a2..45495eff73 100755 --- a/moveit_kinematics/ikfast_kinematics_plugin/scripts/create_ikfast_moveit_plugin.py +++ b/moveit_kinematics/ikfast_kinematics_plugin/scripts/create_ikfast_moveit_plugin.py @@ -251,7 +251,7 @@ def create_ikfast_package(args): def find_template_dir(): for candidate in [os.path.dirname(__file__) + "/../templates"]: - if os.path.exists(candidate) and os.path.exists(candidate + "/ikfast.hpp"): + if os.path.exists(candidate) and os.path.exists(candidate + "/ikfast.h"): return os.path.realpath(candidate) try: return os.path.join( @@ -303,8 +303,8 @@ def update_ikfast_package(args): # Copy ikfast header file copy_file( - template_dir + "/ikfast.hpp", - args.ikfast_plugin_pkg_path + "/include/ikfast.hpp", + template_dir + "/ikfast.h", + args.ikfast_plugin_pkg_path + "/include/ikfast.h", "ikfast header file", ) # Create ikfast plugin template diff --git a/moveit_kinematics/ikfast_kinematics_plugin/templates/ikfast.hpp b/moveit_kinematics/ikfast_kinematics_plugin/templates/ikfast.h similarity index 100% rename from moveit_kinematics/ikfast_kinematics_plugin/templates/ikfast.hpp rename to moveit_kinematics/ikfast_kinematics_plugin/templates/ikfast.h diff --git a/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/src/prbt_manipulator_ikfast_solver.cpp b/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/src/prbt_manipulator_ikfast_solver.cpp index 870c0f8fea..8741aa7cce 100644 --- a/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/src/prbt_manipulator_ikfast_solver.cpp +++ b/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/src/prbt_manipulator_ikfast_solver.cpp @@ -22,11 +22,11 @@ /// To compile without any main function as a shared object (might need -llapack): /// gcc -fPIC -lstdc++ -DIKFAST_NO_MAIN -DIKFAST_CLIBRARY -shared -Wl,-soname,libik.so -o libik.so ik.cpp #define IKFAST_HAS_LIBRARY -#include "ikfast.hpp" // found inside share/openrave-X.Y/python/ikfast.hpp +#include "ikfast.h" // found inside share/openrave-X.Y/python/ikfast.h using namespace ikfast; // check if the included ikfast version matches what this file was compiled with -static_assert(IKFAST_VERSION==61); // version found in ikfast.hpp +static_assert(IKFAST_VERSION==61); // version found in ikfast.h #include #include From 0d2080ddea56317c6a5512bb55954f4925df9420 Mon Sep 17 00:00:00 2001 From: Tom Noble <53005340+TSNoble@users.noreply.github.com> Date: Mon, 18 Nov 2024 17:04:18 +0000 Subject: [PATCH 20/53] Rename ikfast.hpp to ikfast.h --- .../include/{ikfast.hpp => ikfast.h} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/include/{ikfast.hpp => ikfast.h} (100%) diff --git a/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/include/ikfast.hpp b/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/include/ikfast.h similarity index 100% rename from moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/include/ikfast.hpp rename to moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/include/ikfast.h From 7eb5cc2c5a7daff2f866016f15fde22fd047a0da Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Mon, 18 Nov 2024 18:52:39 +0000 Subject: [PATCH 21/53] Applies changes from d529029062305520817c261be6601bab94b21255 --- MIGRATION.md | 5 +- .../collision_detection/collision_common.hpp | 6 ++ .../moveit/planning_scene/planning_scene.hpp | 95 ++++++------------- 3 files changed, 35 insertions(+), 71 deletions(-) diff --git a/MIGRATION.md b/MIGRATION.md index e6ba8a8d6c..3aa22d5f05 100644 --- a/MIGRATION.md +++ b/MIGRATION.md @@ -3,9 +3,8 @@ API changes in MoveIt releases ## ROS Rolling -- [11/2024] All MoveIt 2 headers have been updated to use the `.hpp` extension. -`.h` headers are now autogenerated with a deprecation warning, and may be removed in future releases. -Please update your imports to use the `.hpp` headers. +- [11/2024] Added flags to control padding to CollisionRequest. This change deprecates PlanningScene::checkCollisionUnpadded(..) functions. Please use PlanningScene::checkCollision(..) with a req.pad_environment_collisions = false; + - [12/2023] `trajectory_processing::Path` and `trajectory_processing::Trajectory` APIs have been updated to prevent misuse. The constructors have been replaced by builder methods so that errors can be communicated. Paths and trajectories now need to be created with `Path::Create()` and `Trajectory::Create()`. These methods now return an `std::optional` that needs to be checked for a valid value. `Trajectory` no longer has the `isValid()` method. If it's invalid, `Trajectory::Create()` will return `std::nullopt`. Finally, `Path` now takes the list of input waypoints as `std::vector`, instead of `std::list`. - [12/2023] LMA kinematics plugin is removed to remove the maintenance work because better alternatives exist like KDL or TracIK diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.hpp b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.hpp index 49d12da47d..19777a044f 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.hpp +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.hpp @@ -150,6 +150,12 @@ struct CollisionRequest * are included. */ std::string group_name = ""; + /** \brief If true, use padded collision environment */ + bool pad_environment_collisions = true; + + /** \brief If true, do self collision check with padded robot links */ + bool pad_self_collisions = false; + /** \brief If true, compute proximity distance */ bool distance = false; diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.hpp b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.hpp index 7141900012..a141b9f7e5 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.hpp +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.hpp @@ -347,19 +347,12 @@ class MOVEIT_PLANNING_SCENE_EXPORT PlanningScene : public std::enable_shared_fro void checkCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res); /** \brief Check whether the current state is in collision. The current state is expected to be updated. */ - void checkCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res) const - { - checkCollision(req, res, getCurrentState()); - } + void checkCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res) const; /** \brief Check whether a specified state (\e robot_state) is in collision. This variant of the function takes a non-const \e robot_state and calls updateCollisionBodyTransforms() on it. */ void checkCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - moveit::core::RobotState& robot_state) const - { - robot_state.updateCollisionBodyTransforms(); - checkCollision(req, res, static_cast(robot_state)); - } + moveit::core::RobotState& robot_state) const; /** \brief Check whether a specified state (\e robot_state) is in collision. The collision transforms of \e * robot_state are @@ -372,11 +365,7 @@ class MOVEIT_PLANNING_SCENE_EXPORT PlanningScene : public std::enable_shared_fro a non-const \e robot_state and updates its link transforms if needed. */ void checkCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, moveit::core::RobotState& robot_state, - const collision_detection::AllowedCollisionMatrix& acm) const - { - robot_state.updateCollisionBodyTransforms(); - checkCollision(req, res, static_cast(robot_state), acm); - } + const collision_detection::AllowedCollisionMatrix& acm) const; /** \brief Check whether a specified state (\e robot_state) is in collision, with respect to a given allowed collision matrix (\e acm). */ @@ -387,99 +376,69 @@ class MOVEIT_PLANNING_SCENE_EXPORT PlanningScene : public std::enable_shared_fro /** \brief Check whether the current state is in collision, but use a collision_detection::CollisionRobot instance that has no padding. Since the function is non-const, the current state transforms are also updated if needed. */ - void checkCollisionUnpadded(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res); + [[deprecated("Use new CollisionRequest flags to enable/ disable padding instead.")]] void + checkCollisionUnpadded(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res); /** \brief Check whether the current state is in collision, but use a collision_detection::CollisionRobot instance that has no padding. */ - void checkCollisionUnpadded(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res) const - { - checkCollisionUnpadded(req, res, getCurrentState(), getAllowedCollisionMatrix()); - } + [[deprecated("Use new CollisionRequest flags to enable/ disable padding instead.")]] void + checkCollisionUnpadded(const collision_detection::CollisionRequest& req, + collision_detection::CollisionResult& res) const; /** \brief Check whether a specified state (\e robot_state) is in collision, but use a collision_detection::CollisionRobot instance that has no padding. */ - void checkCollisionUnpadded(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res, - const moveit::core::RobotState& robot_state) const - { - checkCollisionUnpadded(req, res, robot_state, getAllowedCollisionMatrix()); - } + [[deprecated("Use new CollisionRequest flags to enable/ disable padding instead.")]] void + checkCollisionUnpadded(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, + const moveit::core::RobotState& robot_state) const; /** \brief Check whether a specified state (\e robot_state) is in collision, but use a collision_detection::CollisionRobot instance that has no padding. Update the link transforms of \e robot_state if needed. */ - void checkCollisionUnpadded(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res, moveit::core::RobotState& robot_state) const - { - robot_state.updateCollisionBodyTransforms(); - checkCollisionUnpadded(req, res, static_cast(robot_state), - getAllowedCollisionMatrix()); - } + [[deprecated("Use new CollisionRequest flags to enable/ disable padding instead.")]] void + checkCollisionUnpadded(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, + moveit::core::RobotState& robot_state) const; /** \brief Check whether a specified state (\e robot_state) is in collision, with respect to a given allowed collision matrix (\e acm), but use a collision_detection::CollisionRobot instance that has no padding. This variant of the function takes a non-const \e robot_state and calls updates the link transforms if needed. */ - void checkCollisionUnpadded(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res, moveit::core::RobotState& robot_state, - const collision_detection::AllowedCollisionMatrix& acm) const - { - robot_state.updateCollisionBodyTransforms(); - checkCollisionUnpadded(req, res, static_cast(robot_state), acm); - } + [[deprecated("Use new CollisionRequest flags to enable/ disable padding instead.")]] void + checkCollisionUnpadded(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, + moveit::core::RobotState& robot_state, + const collision_detection::AllowedCollisionMatrix& acm) const; /** \brief Check whether a specified state (\e robot_state) is in collision, with respect to a given allowed collision matrix (\e acm), but use a collision_detection::CollisionRobot instance that has no padding. */ - void checkCollisionUnpadded(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res, const moveit::core::RobotState& robot_state, - const collision_detection::AllowedCollisionMatrix& acm) const; + [[deprecated("Use new CollisionRequest flags to enable/ disable padding instead.")]] void + checkCollisionUnpadded(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, + const moveit::core::RobotState& robot_state, + const collision_detection::AllowedCollisionMatrix& acm) const; /** \brief Check whether the current state is in self collision */ void checkSelfCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res); /** \brief Check whether the current state is in self collision */ void checkSelfCollision(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res) const - { - checkSelfCollision(req, res, getCurrentState()); - } + collision_detection::CollisionResult& res) const; /** \brief Check whether a specified state (\e robot_state) is in self collision */ void checkSelfCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - moveit::core::RobotState& robot_state) const - { - robot_state.updateCollisionBodyTransforms(); - checkSelfCollision(req, res, static_cast(robot_state), getAllowedCollisionMatrix()); - } + moveit::core::RobotState& robot_state) const; /** \brief Check whether a specified state (\e robot_state) is in self collision */ void checkSelfCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - const moveit::core::RobotState& robot_state) const - { - // do self-collision checking with the unpadded version of the robot - getCollisionEnvUnpadded()->checkSelfCollision(req, res, robot_state, getAllowedCollisionMatrix()); - } + const moveit::core::RobotState& robot_state) const; /** \brief Check whether a specified state (\e robot_state) is in self collision, with respect to a given allowed collision matrix (\e acm). The link transforms of \e robot_state are updated if needed. */ void checkSelfCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, moveit::core::RobotState& robot_state, - const collision_detection::AllowedCollisionMatrix& acm) const - { - robot_state.updateCollisionBodyTransforms(); - checkSelfCollision(req, res, static_cast(robot_state), acm); - } + const collision_detection::AllowedCollisionMatrix& acm) const; /** \brief Check whether a specified state (\e robot_state) is in self collision, with respect to a given allowed collision matrix (\e acm) */ void checkSelfCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, const moveit::core::RobotState& robot_state, - const collision_detection::AllowedCollisionMatrix& acm) const - { - // do self-collision checking with the unpadded version of the robot - getCollisionEnvUnpadded()->checkSelfCollision(req, res, robot_state, acm); - } + const collision_detection::AllowedCollisionMatrix& acm) const; /** \brief Get the names of the links that are involved in collisions for the current state */ void getCollidingLinks(std::vector& links); From 4028c1374e6c1d24553d694e075ee4fc948a6e30 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Mon, 18 Nov 2024 18:57:11 +0000 Subject: [PATCH 22/53] Applies changes from d529029062305520817c261be6601bab94b21255 --- .../include/moveit/planning_scene/planning_scene.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.hpp b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.hpp index a141b9f7e5..7271a080df 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.hpp +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.hpp @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include #include #include #include From 6e6f30076ba2794e60653874aca061f288660816 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Mon, 18 Nov 2024 19:04:43 +0000 Subject: [PATCH 23/53] Fixes typos --- MIGRATION.md | 105 ------------------ .../moveit/planning_scene/planning_scene.hpp | 4 +- 2 files changed, 2 insertions(+), 107 deletions(-) delete mode 100644 MIGRATION.md diff --git a/MIGRATION.md b/MIGRATION.md deleted file mode 100644 index 3aa22d5f05..0000000000 --- a/MIGRATION.md +++ /dev/null @@ -1,105 +0,0 @@ -# Migration Notes - -API changes in MoveIt releases - -## ROS Rolling -- [11/2024] Added flags to control padding to CollisionRequest. This change deprecates PlanningScene::checkCollisionUnpadded(..) functions. Please use PlanningScene::checkCollision(..) with a req.pad_environment_collisions = false; - -- [12/2023] `trajectory_processing::Path` and `trajectory_processing::Trajectory` APIs have been updated to prevent misuse. -The constructors have been replaced by builder methods so that errors can be communicated. Paths and trajectories now need to be created with `Path::Create()` and `Trajectory::Create()`. These methods now return an `std::optional` that needs to be checked for a valid value. `Trajectory` no longer has the `isValid()` method. If it's invalid, `Trajectory::Create()` will return `std::nullopt`. Finally, `Path` now takes the list of input waypoints as `std::vector`, instead of `std::list`. -- [12/2023] LMA kinematics plugin is removed to remove the maintenance work because better alternatives exist like KDL or TracIK -- [10/2023] The planning pipeline now has a vector of planner plugins rather than a single one. Please update the planner plugin parameter e.g. like this: -```diff -- planning_plugin: ompl_interface/OMPLPlanner -+ planning_plugins: -+ - ompl_interface/OMPLPlanner -``` -- [10/2023] Planning request adapters are now separated into PlanRequest (preprocessing) and PlanResponse (postprocessing) adapters. The adapters are configured with ROS parameter vectors (vector order corresponds to execution order). Please update your pipeline configurations for example like this: -```diff -- request_adapters: >- -- default_planner_request_adapters/AddTimeOptimalParameterization -- default_planner_request_adapters/ResolveConstraintFrames -- default_planner_request_adapters/FixWorkspaceBounds -- default_planner_request_adapters/FixStartStateBounds -- default_planner_request_adapters/FixStartStateCollision -- default_planner_request_adapters/FixStartStatePathConstraints -+ # The order of the elements in the adapter corresponds to the order they are processed by the motion planning pipeline. -+ request_adapters: -+ - default_planning_request_adapters/ResolveConstraintFrames -+ - default_planning_request_adapters/ValidateWorkspaceBounds -+ - default_planning_request_adapters/CheckStartStateBounds -+ - default_planning_request_adapters/CheckStartStateCollision -+ response_adapters: -+ - default_planning_response_adapters/AddTimeOptimalParameterization -+ - default_planning_response_adapters/ValidateSolution -+ - default_planning_response_adapters/DisplayMotionPath -``` -- [2021] `lockSceneRead()` and `lockSceneWrite()` are now protected member functions, for internal use only. To lock the planning scene, use ``LockedPlanningSceneRO`` or ``LockedPlanningSceneRW``: -``` - planning_scene_monitor::LockedPlanningSceneRO ls(planning_scene_monitor); - moveit::core::RobotModelConstPtr model = ls->getRobotModel(); -``` -- [2021] ServoServer was renamed to ServoNode -- [2021] `CollisionObject` messages are now defined with a `Pose`, and shapes and subframes are defined relative to the object's pose. This makes it easier to place objects with subframes and multiple shapes in the scene. This causes several changes: - - `getFrameTransform()` now returns this pose instead of the first shape's pose. - - The Rviz plugin's manipulation tab now uses the object's pose instead of the shape pose to evaluate if object's are in the region of interest. - - Planning scene geometry text files (`.scene`) have changed format. Loading old files is still supported. You can add a line `0 0 0 0 0 0 1` under each line with an asterisk to upgrade old files. -- [2021] Add API for passing RNG to setToRandomPositionsNearBy -- [2021] Static member variable interface of the CollisionDetectorAllocatorTemplate for the string NAME was replaced with a virtual method `getName`. -- [2021] Enhance `RDFLoader` to load from string parameter OR string topic (and add the ability to publish a string topic). - -## ROS Noetic -- RobotModel no longer overrides empty URDF collision geometry by matching the visual geometry of the link. -- Planned trajectories are *slow* by default. - The default values of the `velocity_scaling_factor` and `acceleration_scaling_factor` can now be customized and default to 0.1 instead of 1.0. - The values can be changed by setting the parameters `default_acceleration_scaling_factor` and `default_velocity_scaling_factor` in the `joint_limits.yaml` of your robot's `moveit_config` package. - Consider setting them to values between 0.2 and 0.6, to allow for significant speedup/slowdown of your application. - Additionally, you can always change the factors per request with the corresponding methods in the [move_group_interface](http://docs.ros.org/melodic/api/moveit_ros_planning_interface/html/classmoveit_1_1planning__interface_1_1MoveGroupInterface.html#a3e2bd2edccca8aa49a6bec9d039d5bf3), the [MoveGroupCommander](http://docs.ros.org/melodic/api/moveit_commander/html/classmoveit__commander_1_1move__group_1_1MoveGroupCommander.html#a7706effa66a0847496de477cf219a562) or in the Rviz interface. ([1890](https://github.com/ros-planning/moveit/pull/1890)) -- Extended the return value of `MoveitCommander.MoveGroup.plan()` from `trajectory` to a tuple of `(success, trajectory, planning_time, error_code)` to better match the C++ MoveGroupInterface ([790](https://github.com/ros-planning/moveit/pull/790/)) -- `moveit_rviz.launch`, generated by MSA, provides an argument `rviz_config` to configure the rviz config to be used. The old boolean config argument was dropped. ([1397](https://github.com/ros-planning/moveit/pull/1397)) -- Moved the example package `moveit_controller_manager_example` into [moveit_tutorials](https://github.com/ros-planning/moveit_tutorials) -- Requests to `get_planning_scene` service without explicitly setting "components" now return full scene -- `moveit_ros_planning` no longer depends on `moveit_ros_perception` -- `CollisionRobot` and `CollisionWorld` are combined into a single `CollisionEnv` class. This applies for all derived collision checkers as `FCL`, `ALL_VALID`, `HYBRID` and `DISTANCE_FIELD`. Consequently, `getCollisionRobot[Unpadded] / getCollisionWorld` functions are replaced through a `getCollisionEnv` in the planning scene and return the new combined environment. This unified collision environment provides the union of all member functions of `CollisionRobot` and `CollisionWorld`. Note that calling `checkRobotCollision` of the `CollisionEnv` does not take a `CollisionRobot` as an argument anymore as it is implicitly contained in the `CollisionEnv`. -- `RobotTrajectory` provides a copy constructor that allows a shallow (default) and deep copy of waypoints -- Replace the redundant namespaces `robot_state::` and `robot_model::` with the actual namespace `moveit::core::`. The additional namespaces will disappear in the future (ROS2). -- Moved the library `moveit_cpp` to `moveit_ros_planning`. The classes are now in namespace `moveit_cpp`, access via `moveit::planning_interface` is deprecated. -- The joint states of `passive` joints must be published in ROS and the CurrentStateMonitor will now wait for them as well. Their semantics dictate that they cannot be actively controlled, but they must be known to use the full robot state in collision checks. (https://github.com/ros-planning/moveit/pull/2663) -- Removed deprecated header `moveit/macros/deprecation.h`. Use `[[deprecated]]` instead. -- All uses of `MOVEIT_CLASS_FORWARD` et. al. must now be followed by a semicolon for consistency (and to get -pedantic builds to pass for the codebase). -- In case you start RViz in a namespace, the default topic for the trajectory visualization display now uses the relative instead of the absolute namespace (i.e. `/move_group/display_planned_path` instead of `/move_group/display_planned_path`). -- `RobotState::attachBody()` now takes a unique_ptr instead of an owning raw pointer. -- Moved the class `MoveItErrorCode` from both `moveit_ros_planning` and `moveit_ros_planning_interface` to `moveit_core`. The class now is in namespace `moveit::core`, access via `moveit::planning_interface` or `moveit_cpp::PlanningComponent` is deprecated. -- End-effector markers in rviz are shown only if the eef's parent group is active _and_ the parent link is part of that group. Before, these conditions were _OR_-connected. - You might need to define additional end-effectors. -- Removed `ConstraintSampler::project()` as there was no real difference to `sample()`. -- Removed `TrajectoryExecutionManager::pushAndExecute()` and the code associated to it. The code was unused and broken. - -## ROS Melodic - -- Migration to ``tf2`` API. -- Replaced Eigen::Affine3d with Eigen::Isometry3d, which is computationally more efficient. - Simply find-replace occurrences of Affine3d: - ``find . -iname "*.[hc]*" -print0 | xargs -0 sed -i 's#Affine3#Isometry3#g'`` -- The move_group capability ``ExecuteTrajectoryServiceCapability`` has been removed in favor of the improved ``ExecuteTrajectoryActionCapability`` capability. Since Indigo, both capabilities were supported. If you still load default capabilities in your ``config/launch/move_group.launch``, you can just remove them from the capabilities parameter. The correct default capabilities will be loaded automatically. -- Deprecated method ``CurrentStateMonitor::waitForCurrentState(double wait_time)`` was finally removed. -- Renamed ``RobotState::getCollisionBodyTransforms`` to ``getCollisionBodyTransform`` as it returns a single transform only. -- Removed deprecated class MoveGroup (was renamed to MoveGroupInterface). -- KinematicsBase: Deprecated members `tip_frame_`, `search_discretization_`. - Use `tip_frames_` and `redundant_joint_discretization_` instead. -- KinematicsBase: Deprecated `initialize(robot_description, ...)` in favour of `initialize(robot_model, ...)`. - Adapt your kinematics plugin to directly receive a `RobotModel`. See the [KDL plugin](https://github.com/ros-planning/moveit/tree/melodic-devel/moveit_kinematics/kdl_kinematics_plugin) for an example. -- IK: Removed notion of IK attempts and redundant random seeding in RobotState::setFromIK(). Number of attempts is limited by timeout only. ([#1288](https://github.com/ros-planning/moveit/pull/1288)) - Remove parameters `kinematics_solver_attempts` from your `kinematics.yaml` config files. -- ``RDFLoader`` / ``RobotModelLoader``: removed TinyXML-based API (https://github.com/ros-planning/moveit/pull/1254) -- Deprecated `EndEffectorInteractionStyle` got removed from `RobotInteraction` (https://github.com/ros-planning/moveit/pull/1287) - Use [the corresponding `InteractionStyle` definitions](https://github.com/ros-planning/moveit/pull/1287/files#diff-24e57a8ea7f2f2d8a63cfc31580d09ddL240) instead - -## ROS Kinetic - -- In the C++ MoveGroupInterface class the ``plan()`` method returns a ``MoveItErrorCode`` object and not a boolean. - `static_cast(mgi.plan())` can be used to achieve the old behavior. -- ``CurrentStateMonitor::waitForCurrentState(double wait_time)`` has been renamed to ``waitForCompleteState`` to better reflect the actual semantics. Additionally a new method ``waitForCurrentState(const ros::Time t = ros::Time::now())`` was added that actually waits until all joint updates are newer than ``t``. -- To avoid deadlocks, the PlanningSceneMonitor listens to its own EventQueue, monitored by an additional spinner thread. - Providing a custom NodeHandle, a user can control which EventQueue and processing thread is used instead. - Providing a default NodeHandle, the old behavior (using the global EventQueue) can be restored, which is however not recommended. diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.hpp b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.hpp index 7271a080df..a141b9f7e5 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.hpp +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.hpp @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include #include #include #include From 3c0ad59f91cab0ffb7120ece9b4faa724bab40da Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Mon, 18 Nov 2024 19:21:19 +0000 Subject: [PATCH 24/53] Reverts botched merge --- MIGRATION.md | 106 ++++++++++++++++++ .../collision_detection/collision_common.hpp | 6 - .../moveit/planning_scene/planning_scene.hpp | 95 +++++++++++----- 3 files changed, 174 insertions(+), 33 deletions(-) create mode 100644 MIGRATION.md diff --git a/MIGRATION.md b/MIGRATION.md new file mode 100644 index 0000000000..e6ba8a8d6c --- /dev/null +++ b/MIGRATION.md @@ -0,0 +1,106 @@ +# Migration Notes + +API changes in MoveIt releases + +## ROS Rolling +- [11/2024] All MoveIt 2 headers have been updated to use the `.hpp` extension. +`.h` headers are now autogenerated with a deprecation warning, and may be removed in future releases. +Please update your imports to use the `.hpp` headers. +- [12/2023] `trajectory_processing::Path` and `trajectory_processing::Trajectory` APIs have been updated to prevent misuse. +The constructors have been replaced by builder methods so that errors can be communicated. Paths and trajectories now need to be created with `Path::Create()` and `Trajectory::Create()`. These methods now return an `std::optional` that needs to be checked for a valid value. `Trajectory` no longer has the `isValid()` method. If it's invalid, `Trajectory::Create()` will return `std::nullopt`. Finally, `Path` now takes the list of input waypoints as `std::vector`, instead of `std::list`. +- [12/2023] LMA kinematics plugin is removed to remove the maintenance work because better alternatives exist like KDL or TracIK +- [10/2023] The planning pipeline now has a vector of planner plugins rather than a single one. Please update the planner plugin parameter e.g. like this: +```diff +- planning_plugin: ompl_interface/OMPLPlanner ++ planning_plugins: ++ - ompl_interface/OMPLPlanner +``` +- [10/2023] Planning request adapters are now separated into PlanRequest (preprocessing) and PlanResponse (postprocessing) adapters. The adapters are configured with ROS parameter vectors (vector order corresponds to execution order). Please update your pipeline configurations for example like this: +```diff +- request_adapters: >- +- default_planner_request_adapters/AddTimeOptimalParameterization +- default_planner_request_adapters/ResolveConstraintFrames +- default_planner_request_adapters/FixWorkspaceBounds +- default_planner_request_adapters/FixStartStateBounds +- default_planner_request_adapters/FixStartStateCollision +- default_planner_request_adapters/FixStartStatePathConstraints ++ # The order of the elements in the adapter corresponds to the order they are processed by the motion planning pipeline. ++ request_adapters: ++ - default_planning_request_adapters/ResolveConstraintFrames ++ - default_planning_request_adapters/ValidateWorkspaceBounds ++ - default_planning_request_adapters/CheckStartStateBounds ++ - default_planning_request_adapters/CheckStartStateCollision ++ response_adapters: ++ - default_planning_response_adapters/AddTimeOptimalParameterization ++ - default_planning_response_adapters/ValidateSolution ++ - default_planning_response_adapters/DisplayMotionPath +``` +- [2021] `lockSceneRead()` and `lockSceneWrite()` are now protected member functions, for internal use only. To lock the planning scene, use ``LockedPlanningSceneRO`` or ``LockedPlanningSceneRW``: +``` + planning_scene_monitor::LockedPlanningSceneRO ls(planning_scene_monitor); + moveit::core::RobotModelConstPtr model = ls->getRobotModel(); +``` +- [2021] ServoServer was renamed to ServoNode +- [2021] `CollisionObject` messages are now defined with a `Pose`, and shapes and subframes are defined relative to the object's pose. This makes it easier to place objects with subframes and multiple shapes in the scene. This causes several changes: + - `getFrameTransform()` now returns this pose instead of the first shape's pose. + - The Rviz plugin's manipulation tab now uses the object's pose instead of the shape pose to evaluate if object's are in the region of interest. + - Planning scene geometry text files (`.scene`) have changed format. Loading old files is still supported. You can add a line `0 0 0 0 0 0 1` under each line with an asterisk to upgrade old files. +- [2021] Add API for passing RNG to setToRandomPositionsNearBy +- [2021] Static member variable interface of the CollisionDetectorAllocatorTemplate for the string NAME was replaced with a virtual method `getName`. +- [2021] Enhance `RDFLoader` to load from string parameter OR string topic (and add the ability to publish a string topic). + +## ROS Noetic +- RobotModel no longer overrides empty URDF collision geometry by matching the visual geometry of the link. +- Planned trajectories are *slow* by default. + The default values of the `velocity_scaling_factor` and `acceleration_scaling_factor` can now be customized and default to 0.1 instead of 1.0. + The values can be changed by setting the parameters `default_acceleration_scaling_factor` and `default_velocity_scaling_factor` in the `joint_limits.yaml` of your robot's `moveit_config` package. + Consider setting them to values between 0.2 and 0.6, to allow for significant speedup/slowdown of your application. + Additionally, you can always change the factors per request with the corresponding methods in the [move_group_interface](http://docs.ros.org/melodic/api/moveit_ros_planning_interface/html/classmoveit_1_1planning__interface_1_1MoveGroupInterface.html#a3e2bd2edccca8aa49a6bec9d039d5bf3), the [MoveGroupCommander](http://docs.ros.org/melodic/api/moveit_commander/html/classmoveit__commander_1_1move__group_1_1MoveGroupCommander.html#a7706effa66a0847496de477cf219a562) or in the Rviz interface. ([1890](https://github.com/ros-planning/moveit/pull/1890)) +- Extended the return value of `MoveitCommander.MoveGroup.plan()` from `trajectory` to a tuple of `(success, trajectory, planning_time, error_code)` to better match the C++ MoveGroupInterface ([790](https://github.com/ros-planning/moveit/pull/790/)) +- `moveit_rviz.launch`, generated by MSA, provides an argument `rviz_config` to configure the rviz config to be used. The old boolean config argument was dropped. ([1397](https://github.com/ros-planning/moveit/pull/1397)) +- Moved the example package `moveit_controller_manager_example` into [moveit_tutorials](https://github.com/ros-planning/moveit_tutorials) +- Requests to `get_planning_scene` service without explicitly setting "components" now return full scene +- `moveit_ros_planning` no longer depends on `moveit_ros_perception` +- `CollisionRobot` and `CollisionWorld` are combined into a single `CollisionEnv` class. This applies for all derived collision checkers as `FCL`, `ALL_VALID`, `HYBRID` and `DISTANCE_FIELD`. Consequently, `getCollisionRobot[Unpadded] / getCollisionWorld` functions are replaced through a `getCollisionEnv` in the planning scene and return the new combined environment. This unified collision environment provides the union of all member functions of `CollisionRobot` and `CollisionWorld`. Note that calling `checkRobotCollision` of the `CollisionEnv` does not take a `CollisionRobot` as an argument anymore as it is implicitly contained in the `CollisionEnv`. +- `RobotTrajectory` provides a copy constructor that allows a shallow (default) and deep copy of waypoints +- Replace the redundant namespaces `robot_state::` and `robot_model::` with the actual namespace `moveit::core::`. The additional namespaces will disappear in the future (ROS2). +- Moved the library `moveit_cpp` to `moveit_ros_planning`. The classes are now in namespace `moveit_cpp`, access via `moveit::planning_interface` is deprecated. +- The joint states of `passive` joints must be published in ROS and the CurrentStateMonitor will now wait for them as well. Their semantics dictate that they cannot be actively controlled, but they must be known to use the full robot state in collision checks. (https://github.com/ros-planning/moveit/pull/2663) +- Removed deprecated header `moveit/macros/deprecation.h`. Use `[[deprecated]]` instead. +- All uses of `MOVEIT_CLASS_FORWARD` et. al. must now be followed by a semicolon for consistency (and to get -pedantic builds to pass for the codebase). +- In case you start RViz in a namespace, the default topic for the trajectory visualization display now uses the relative instead of the absolute namespace (i.e. `/move_group/display_planned_path` instead of `/move_group/display_planned_path`). +- `RobotState::attachBody()` now takes a unique_ptr instead of an owning raw pointer. +- Moved the class `MoveItErrorCode` from both `moveit_ros_planning` and `moveit_ros_planning_interface` to `moveit_core`. The class now is in namespace `moveit::core`, access via `moveit::planning_interface` or `moveit_cpp::PlanningComponent` is deprecated. +- End-effector markers in rviz are shown only if the eef's parent group is active _and_ the parent link is part of that group. Before, these conditions were _OR_-connected. + You might need to define additional end-effectors. +- Removed `ConstraintSampler::project()` as there was no real difference to `sample()`. +- Removed `TrajectoryExecutionManager::pushAndExecute()` and the code associated to it. The code was unused and broken. + +## ROS Melodic + +- Migration to ``tf2`` API. +- Replaced Eigen::Affine3d with Eigen::Isometry3d, which is computationally more efficient. + Simply find-replace occurrences of Affine3d: + ``find . -iname "*.[hc]*" -print0 | xargs -0 sed -i 's#Affine3#Isometry3#g'`` +- The move_group capability ``ExecuteTrajectoryServiceCapability`` has been removed in favor of the improved ``ExecuteTrajectoryActionCapability`` capability. Since Indigo, both capabilities were supported. If you still load default capabilities in your ``config/launch/move_group.launch``, you can just remove them from the capabilities parameter. The correct default capabilities will be loaded automatically. +- Deprecated method ``CurrentStateMonitor::waitForCurrentState(double wait_time)`` was finally removed. +- Renamed ``RobotState::getCollisionBodyTransforms`` to ``getCollisionBodyTransform`` as it returns a single transform only. +- Removed deprecated class MoveGroup (was renamed to MoveGroupInterface). +- KinematicsBase: Deprecated members `tip_frame_`, `search_discretization_`. + Use `tip_frames_` and `redundant_joint_discretization_` instead. +- KinematicsBase: Deprecated `initialize(robot_description, ...)` in favour of `initialize(robot_model, ...)`. + Adapt your kinematics plugin to directly receive a `RobotModel`. See the [KDL plugin](https://github.com/ros-planning/moveit/tree/melodic-devel/moveit_kinematics/kdl_kinematics_plugin) for an example. +- IK: Removed notion of IK attempts and redundant random seeding in RobotState::setFromIK(). Number of attempts is limited by timeout only. ([#1288](https://github.com/ros-planning/moveit/pull/1288)) + Remove parameters `kinematics_solver_attempts` from your `kinematics.yaml` config files. +- ``RDFLoader`` / ``RobotModelLoader``: removed TinyXML-based API (https://github.com/ros-planning/moveit/pull/1254) +- Deprecated `EndEffectorInteractionStyle` got removed from `RobotInteraction` (https://github.com/ros-planning/moveit/pull/1287) + Use [the corresponding `InteractionStyle` definitions](https://github.com/ros-planning/moveit/pull/1287/files#diff-24e57a8ea7f2f2d8a63cfc31580d09ddL240) instead + +## ROS Kinetic + +- In the C++ MoveGroupInterface class the ``plan()`` method returns a ``MoveItErrorCode`` object and not a boolean. + `static_cast(mgi.plan())` can be used to achieve the old behavior. +- ``CurrentStateMonitor::waitForCurrentState(double wait_time)`` has been renamed to ``waitForCompleteState`` to better reflect the actual semantics. Additionally a new method ``waitForCurrentState(const ros::Time t = ros::Time::now())`` was added that actually waits until all joint updates are newer than ``t``. +- To avoid deadlocks, the PlanningSceneMonitor listens to its own EventQueue, monitored by an additional spinner thread. + Providing a custom NodeHandle, a user can control which EventQueue and processing thread is used instead. + Providing a default NodeHandle, the old behavior (using the global EventQueue) can be restored, which is however not recommended. diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.hpp b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.hpp index 19777a044f..49d12da47d 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.hpp +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.hpp @@ -150,12 +150,6 @@ struct CollisionRequest * are included. */ std::string group_name = ""; - /** \brief If true, use padded collision environment */ - bool pad_environment_collisions = true; - - /** \brief If true, do self collision check with padded robot links */ - bool pad_self_collisions = false; - /** \brief If true, compute proximity distance */ bool distance = false; diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.hpp b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.hpp index a141b9f7e5..7141900012 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.hpp +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.hpp @@ -347,12 +347,19 @@ class MOVEIT_PLANNING_SCENE_EXPORT PlanningScene : public std::enable_shared_fro void checkCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res); /** \brief Check whether the current state is in collision. The current state is expected to be updated. */ - void checkCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res) const; + void checkCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res) const + { + checkCollision(req, res, getCurrentState()); + } /** \brief Check whether a specified state (\e robot_state) is in collision. This variant of the function takes a non-const \e robot_state and calls updateCollisionBodyTransforms() on it. */ void checkCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - moveit::core::RobotState& robot_state) const; + moveit::core::RobotState& robot_state) const + { + robot_state.updateCollisionBodyTransforms(); + checkCollision(req, res, static_cast(robot_state)); + } /** \brief Check whether a specified state (\e robot_state) is in collision. The collision transforms of \e * robot_state are @@ -365,7 +372,11 @@ class MOVEIT_PLANNING_SCENE_EXPORT PlanningScene : public std::enable_shared_fro a non-const \e robot_state and updates its link transforms if needed. */ void checkCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, moveit::core::RobotState& robot_state, - const collision_detection::AllowedCollisionMatrix& acm) const; + const collision_detection::AllowedCollisionMatrix& acm) const + { + robot_state.updateCollisionBodyTransforms(); + checkCollision(req, res, static_cast(robot_state), acm); + } /** \brief Check whether a specified state (\e robot_state) is in collision, with respect to a given allowed collision matrix (\e acm). */ @@ -376,69 +387,99 @@ class MOVEIT_PLANNING_SCENE_EXPORT PlanningScene : public std::enable_shared_fro /** \brief Check whether the current state is in collision, but use a collision_detection::CollisionRobot instance that has no padding. Since the function is non-const, the current state transforms are also updated if needed. */ - [[deprecated("Use new CollisionRequest flags to enable/ disable padding instead.")]] void - checkCollisionUnpadded(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res); + void checkCollisionUnpadded(const collision_detection::CollisionRequest& req, + collision_detection::CollisionResult& res); /** \brief Check whether the current state is in collision, but use a collision_detection::CollisionRobot instance that has no padding. */ - [[deprecated("Use new CollisionRequest flags to enable/ disable padding instead.")]] void - checkCollisionUnpadded(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res) const; + void checkCollisionUnpadded(const collision_detection::CollisionRequest& req, + collision_detection::CollisionResult& res) const + { + checkCollisionUnpadded(req, res, getCurrentState(), getAllowedCollisionMatrix()); + } /** \brief Check whether a specified state (\e robot_state) is in collision, but use a collision_detection::CollisionRobot instance that has no padding. */ - [[deprecated("Use new CollisionRequest flags to enable/ disable padding instead.")]] void - checkCollisionUnpadded(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - const moveit::core::RobotState& robot_state) const; + void checkCollisionUnpadded(const collision_detection::CollisionRequest& req, + collision_detection::CollisionResult& res, + const moveit::core::RobotState& robot_state) const + { + checkCollisionUnpadded(req, res, robot_state, getAllowedCollisionMatrix()); + } /** \brief Check whether a specified state (\e robot_state) is in collision, but use a collision_detection::CollisionRobot instance that has no padding. Update the link transforms of \e robot_state if needed. */ - [[deprecated("Use new CollisionRequest flags to enable/ disable padding instead.")]] void - checkCollisionUnpadded(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - moveit::core::RobotState& robot_state) const; + void checkCollisionUnpadded(const collision_detection::CollisionRequest& req, + collision_detection::CollisionResult& res, moveit::core::RobotState& robot_state) const + { + robot_state.updateCollisionBodyTransforms(); + checkCollisionUnpadded(req, res, static_cast(robot_state), + getAllowedCollisionMatrix()); + } /** \brief Check whether a specified state (\e robot_state) is in collision, with respect to a given allowed collision matrix (\e acm), but use a collision_detection::CollisionRobot instance that has no padding. This variant of the function takes a non-const \e robot_state and calls updates the link transforms if needed. */ - [[deprecated("Use new CollisionRequest flags to enable/ disable padding instead.")]] void - checkCollisionUnpadded(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - moveit::core::RobotState& robot_state, - const collision_detection::AllowedCollisionMatrix& acm) const; + void checkCollisionUnpadded(const collision_detection::CollisionRequest& req, + collision_detection::CollisionResult& res, moveit::core::RobotState& robot_state, + const collision_detection::AllowedCollisionMatrix& acm) const + { + robot_state.updateCollisionBodyTransforms(); + checkCollisionUnpadded(req, res, static_cast(robot_state), acm); + } /** \brief Check whether a specified state (\e robot_state) is in collision, with respect to a given allowed collision matrix (\e acm), but use a collision_detection::CollisionRobot instance that has no padding. */ - [[deprecated("Use new CollisionRequest flags to enable/ disable padding instead.")]] void - checkCollisionUnpadded(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - const moveit::core::RobotState& robot_state, - const collision_detection::AllowedCollisionMatrix& acm) const; + void checkCollisionUnpadded(const collision_detection::CollisionRequest& req, + collision_detection::CollisionResult& res, const moveit::core::RobotState& robot_state, + const collision_detection::AllowedCollisionMatrix& acm) const; /** \brief Check whether the current state is in self collision */ void checkSelfCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res); /** \brief Check whether the current state is in self collision */ void checkSelfCollision(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res) const; + collision_detection::CollisionResult& res) const + { + checkSelfCollision(req, res, getCurrentState()); + } /** \brief Check whether a specified state (\e robot_state) is in self collision */ void checkSelfCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - moveit::core::RobotState& robot_state) const; + moveit::core::RobotState& robot_state) const + { + robot_state.updateCollisionBodyTransforms(); + checkSelfCollision(req, res, static_cast(robot_state), getAllowedCollisionMatrix()); + } /** \brief Check whether a specified state (\e robot_state) is in self collision */ void checkSelfCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - const moveit::core::RobotState& robot_state) const; + const moveit::core::RobotState& robot_state) const + { + // do self-collision checking with the unpadded version of the robot + getCollisionEnvUnpadded()->checkSelfCollision(req, res, robot_state, getAllowedCollisionMatrix()); + } /** \brief Check whether a specified state (\e robot_state) is in self collision, with respect to a given allowed collision matrix (\e acm). The link transforms of \e robot_state are updated if needed. */ void checkSelfCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, moveit::core::RobotState& robot_state, - const collision_detection::AllowedCollisionMatrix& acm) const; + const collision_detection::AllowedCollisionMatrix& acm) const + { + robot_state.updateCollisionBodyTransforms(); + checkSelfCollision(req, res, static_cast(robot_state), acm); + } /** \brief Check whether a specified state (\e robot_state) is in self collision, with respect to a given allowed collision matrix (\e acm) */ void checkSelfCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, const moveit::core::RobotState& robot_state, - const collision_detection::AllowedCollisionMatrix& acm) const; + const collision_detection::AllowedCollisionMatrix& acm) const + { + // do self-collision checking with the unpadded version of the robot + getCollisionEnvUnpadded()->checkSelfCollision(req, res, robot_state, acm); + } /** \brief Get the names of the links that are involved in collisions for the current state */ void getCollidingLinks(std::vector& links); From 3fa7b06601797996adfff9237389028a04f7cf53 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Mon, 18 Nov 2024 20:27:03 +0000 Subject: [PATCH 25/53] Partially fixes merge conflicts --- MIGRATION.md | 6 +- .../collision_detection/collision_common.h | 371 ++++++ .../moveit/planning_scene/planning_scene.h | 1003 +++++++++++++++++ 3 files changed, 1377 insertions(+), 3 deletions(-) create mode 100644 moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h create mode 100644 moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h diff --git a/MIGRATION.md b/MIGRATION.md index e6ba8a8d6c..b2d6977bc7 100644 --- a/MIGRATION.md +++ b/MIGRATION.md @@ -3,9 +3,9 @@ API changes in MoveIt releases ## ROS Rolling -- [11/2024] All MoveIt 2 headers have been updated to use the `.hpp` extension. -`.h` headers are now autogenerated with a deprecation warning, and may be removed in future releases. -Please update your imports to use the `.hpp` headers. +- [11/2024] All MoveIt 2 headers have been updated to use the .hpp extension. .h headers are now autogenerated with a deprecation warning, and may be removed in future releases. Please update your imports to use the .hpp headers. +- [11/2024] Added flags to control padding to CollisionRequest. This change deprecates PlanningScene::checkCollisionUnpadded(..) functions. Please use PlanningScene::checkCollision(..) with a req.pad_environment_collisions = false; + - [12/2023] `trajectory_processing::Path` and `trajectory_processing::Trajectory` APIs have been updated to prevent misuse. The constructors have been replaced by builder methods so that errors can be communicated. Paths and trajectories now need to be created with `Path::Create()` and `Trajectory::Create()`. These methods now return an `std::optional` that needs to be checked for a valid value. `Trajectory` no longer has the `isValid()` method. If it's invalid, `Trajectory::Create()` will return `std::nullopt`. Finally, `Path` now takes the list of input waypoints as `std::vector`, instead of `std::list`. - [12/2023] LMA kinematics plugin is removed to remove the maintenance work because better alternatives exist like KDL or TracIK diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h new file mode 100644 index 0000000000..0fcd4f9808 --- /dev/null +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h @@ -0,0 +1,371 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include + +namespace collision_detection +{ +MOVEIT_CLASS_FORWARD(AllowedCollisionMatrix); // Defines AllowedCollisionMatrixPtr, ConstPtr, WeakPtr... etc + +/** \brief The types of bodies that are considered for collision */ +namespace BodyTypes +{ +/** \brief The types of bodies that are considered for collision */ +enum Type +{ + /** \brief A link on the robot */ + ROBOT_LINK, + + /** \brief A body attached to a robot link */ + ROBOT_ATTACHED, + + /** \brief A body in the environment */ + WORLD_OBJECT +}; +} // namespace BodyTypes + +/** \brief The types of bodies that are considered for collision */ +using BodyType = BodyTypes::Type; + +/** \brief Definition of a contact point */ +struct Contact +{ + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + /** \brief contact position */ + Eigen::Vector3d pos; + + /** \brief normal unit vector at contact */ + Eigen::Vector3d normal; + + /** \brief depth (penetration between bodies) */ + double depth = 0.0; + + /** \brief The id of the first body involved in the contact */ + std::string body_name_1; + + /** \brief The type of the first body involved in the contact */ + BodyType body_type_1; + + /** \brief The id of the second body involved in the contact */ + std::string body_name_2; + + /** \brief The type of the second body involved in the contact */ + BodyType body_type_2; + + /** \brief The distance percentage between casted poses until collision. + * + * If the value is 0, then the collision occurred in the start pose. If the value is 1, then the collision occurred + * in the end pose. */ + double percent_interpolation = 0.0; + + /** \brief The two nearest points connecting the two bodies */ + Eigen::Vector3d nearest_points[2]; +}; + +/** \brief When collision costs are computed, this structure contains information about the partial cost incurred in a + * particular volume */ +struct CostSource +{ + /// The minimum bound of the AABB defining the volume responsible for this partial cost + std::array aabb_min; + + /// The maximum bound of the AABB defining the volume responsible for this partial cost + std::array aabb_max; + + /// The partial cost (the probability of existence for the object there is a collision with) + double cost = 0.0; + + /// Get the volume of the AABB around the cost source + double getVolume() const + { + return (aabb_max[0] - aabb_min[0]) * (aabb_max[1] - aabb_min[1]) * (aabb_max[2] - aabb_min[2]); + } + + /// Order cost sources so that the most costly source is at the top + bool operator<(const CostSource& other) const + { + double c1 = cost * getVolume(); + double c2 = other.cost * other.getVolume(); + if (c1 > c2) + return true; + if (c1 < c2) + return false; + if (cost < other.cost) + return false; + if (cost > other.cost) + return true; + return aabb_min < other.aabb_min; + } +}; + +struct CollisionResult; + +/** \brief Representation of a collision checking request */ +struct CollisionRequest +{ + /** \brief The group name to check collisions for (optional; if empty, assume the complete robot). Descendent links + * are included. */ + std::string group_name = ""; + + /** \brief If true, use padded collision environment */ + bool pad_environment_collisions = true; + + /** \brief If true, do self collision check with padded robot links */ + bool pad_self_collisions = false; + + /** \brief If true, compute proximity distance */ + bool distance = false; + + /** \brief If true, return detailed distance information. Distance must be set to true as well */ + bool detailed_distance = false; + + /** \brief If true, a collision cost is computed */ + bool cost = false; + + /** \brief If true, compute contacts. Otherwise only a binary collision yes/no is reported. */ + bool contacts = false; + + /** \brief Overall maximum number of contacts to compute */ + std::size_t max_contacts = 1; + + /** \brief Maximum number of contacts to compute per pair of bodies (multiple bodies may be in contact at different + * configurations) */ + std::size_t max_contacts_per_pair = 1; + + /** \brief When costs are computed, this value defines how many of the top cost sources should be returned */ + std::size_t max_cost_sources = 1; + + /** \brief Function call that decides whether collision detection should stop. */ + std::function is_done = nullptr; + + /** \brief Flag indicating whether information about detected collisions should be reported */ + bool verbose = false; +}; + +namespace DistanceRequestTypes +{ +enum DistanceRequestType +{ + GLOBAL, ///< Find the global minimum + SINGLE, ///< Find the global minimum for each pair + LIMITED, ///< Find a limited(max_contacts_per_body) set of contacts for a given pair + ALL ///< Find all the contacts for a given pair +}; +} +using DistanceRequestType = DistanceRequestTypes::DistanceRequestType; + +/** \brief Representation of a distance-reporting request */ +struct DistanceRequest +{ + /*** \brief Compute \e active_components_only_ based on \e req_. This + includes links that are in the kinematic model but outside this group, if those links are descendants of + joints in this group that have their values updated. */ + void enableGroup(const moveit::core::RobotModelConstPtr& robot_model) + { + if (robot_model->hasJointModelGroup(group_name)) + { + active_components_only = &robot_model->getJointModelGroup(group_name)->getUpdatedLinkModelsSet(); + } + else + { + active_components_only = nullptr; + } + } + + /// Indicate if nearest point information should be calculated + bool enable_nearest_points = false; + + /// Indicate if a signed distance should be calculated in a collision. + bool enable_signed_distance = false; + + /// Indicate the type of distance request. If using type=ALL, it is + /// recommended to set max_contacts_per_body to the expected number + /// of contacts per pair because it is used to reserve space. + DistanceRequestType type = DistanceRequestType::GLOBAL; + + /// Maximum number of contacts to store for bodies (multiple bodies may be within distance threshold) + std::size_t max_contacts_per_body = 1; + + /// The group name + std::string group_name = ""; + + /// The set of active components to check + const std::set* active_components_only = nullptr; + + /// The allowed collision matrix used to filter checks + const AllowedCollisionMatrix* acm = nullptr; + + /// Only calculate distances for objects within this threshold to each other. + /// If set, this can significantly reduce the number of queries. + double distance_threshold = std::numeric_limits::max(); + + /// Log debug information + bool verbose = false; + + /// Indicate if gradient should be calculated between each object. + /// This is the normalized vector connecting the closest points on the two objects. + bool compute_gradient = false; +}; + +/** \brief Generic representation of the distance information for a pair of objects */ +// TODO(#267): Enable check - for some reason clang-tidy wants to rename this struct to "i0" +struct DistanceResultsData // NOLINT(readability-identifier-naming) - suppress spurious clang-tidy warning +{ + DistanceResultsData() + { + clear(); + } + + /// The distance between two objects. If two objects are in collision, distance <= 0. + double distance; + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + /// The nearest points + Eigen::Vector3d nearest_points[2]; + + /// The object link names + std::string link_names[2]; + + /// The object body type + BodyType body_types[2]; + + /** Normalized vector connecting closest points (from link_names[0] to link_names[1]) + + Usually, when checking convex to convex, the normal is connecting closest points. + However, FCL in case of non-convex to non-convex or convex to non-convex returns + the contact normal for one of the two triangles that are in contact. */ + Eigen::Vector3d normal; + + /// Clear structure data + void clear() + { + distance = std::numeric_limits::max(); + nearest_points[0].setZero(); + nearest_points[1].setZero(); + body_types[0] = BodyType::WORLD_OBJECT; + body_types[1] = BodyType::WORLD_OBJECT; + link_names[0] = ""; + link_names[1] = ""; + normal.setZero(); + } + + /// Compare if the distance is less than another + bool operator<(const DistanceResultsData& other) + { + return (distance < other.distance); + } + + /// Compare if the distance is greater than another + bool operator>(const DistanceResultsData& other) + { + return (distance > other.distance); + } +}; + +/** \brief Mapping between the names of the collision objects and the DistanceResultData. */ +using DistanceMap = std::map, std::vector >; + +/** \brief Result of a distance request. */ +struct DistanceResult +{ + /// Indicates if two objects were in collision + bool collision = false; + + /// ResultsData for the two objects with the minimum distance + DistanceResultsData minimum_distance; + + /// A map of distance data for each link in the req.active_components_only + DistanceMap distances; + + /// Clear structure data + void clear() + { + collision = false; + minimum_distance.clear(); + distances.clear(); + } +}; + +/** \brief Representation of a collision checking result */ +struct CollisionResult +{ + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + /** \brief Clear a previously stored result */ + void clear() + { + collision = false; + distance = std::numeric_limits::max(); + distance_result.clear(); + contact_count = 0; + contacts.clear(); + cost_sources.clear(); + } + + /** \brief Throttled warning printing the first collision pair, if any. All collisions are logged at DEBUG level */ + void print() const; + + /** \brief True if collision was found, false otherwise */ + bool collision = false; + + /** \brief Closest distance between two bodies */ + double distance = std::numeric_limits::max(); + + /** \brief Distance data for each link */ + DistanceResult distance_result; + + /** \brief Number of contacts returned */ + std::size_t contact_count = 0; + + /** \brief A map returning the pairs of body ids in contact, plus their contact details */ + using ContactMap = std::map, std::vector >; + ContactMap contacts; + + /** \brief These are the individual cost sources when costs are computed */ + std::set cost_sources; +}; +} // namespace collision_detection diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h new file mode 100644 index 0000000000..37d7c9787c --- /dev/null +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h @@ -0,0 +1,1003 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan, Acorn Pooley */ + +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +/** \brief This namespace includes the central class for representing planning contexts */ +namespace planning_scene +{ +MOVEIT_CLASS_FORWARD(PlanningScene); // Defines PlanningScenePtr, ConstPtr, WeakPtr... etc + +/** \brief This is the function signature for additional feasibility checks to be imposed on states (in addition to + respecting constraints and collision avoidance). + The first argument is the state to check the feasibility for, the second one is whether the check should be verbose + or not. */ +typedef std::function StateFeasibilityFn; + +/** \brief This is the function signature for additional feasibility checks to be imposed on motions segments between + states (in addition to respecting constraints and collision avoidance). + The order of the arguments matters: the notion of feasibility is to be checked for motion segments that start at the + first state and end at the second state. The third argument indicates + whether the check should be verbose or not. */ +using MotionFeasibilityFn = std::function; + +/** \brief A map from object names (e.g., attached bodies, collision objects) to their colors */ +using ObjectColorMap = std::map; + +/** \brief A map from object names (e.g., attached bodies, collision objects) to their types */ +using ObjectTypeMap = std::map; + +/** \brief This class maintains the representation of the + environment as seen by a planning instance. The environment + geometry, the robot geometry and state are maintained. */ +class MOVEIT_PLANNING_SCENE_EXPORT PlanningScene : public std::enable_shared_from_this +{ +public: + /** + * @brief PlanningScene cannot be copy-constructed + */ + PlanningScene(const PlanningScene&) = delete; + + /** + * @brief PlanningScene cannot be copy-assigned + */ + PlanningScene& operator=(const PlanningScene&) = delete; + + /** \brief construct using an existing RobotModel */ + PlanningScene(const moveit::core::RobotModelConstPtr& robot_model, + const collision_detection::WorldPtr& world = std::make_shared()); + + /** \brief construct using a urdf and srdf. + * A RobotModel for the PlanningScene will be created using the urdf and srdf. */ + PlanningScene(const urdf::ModelInterfaceSharedPtr& urdf_model, const srdf::ModelConstSharedPtr& srdf_model, + const collision_detection::WorldPtr& world = std::make_shared()); + + static const std::string OCTOMAP_NS; + static const std::string DEFAULT_SCENE_NAME; + + ~PlanningScene(); + + /** \brief Get the name of the planning scene. This is empty by default */ + const std::string& getName() const + { + return name_; + } + + /** \brief Set the name of the planning scene */ + void setName(const std::string& name) + { + name_ = name; + } + + /** \brief Return a new child PlanningScene that uses this one as parent. + * + * The child scene has its own copy of the world. It maintains a list (in + * world_diff_) of changes made to the child world. + * + * The robot_model_, robot_state_, scene_transforms_, and acm_ are not copied. + * They are shared with the parent. So if changes to these are made in the parent they will be visible in the child. + * But if any of these is modified (i.e. if the get*NonConst functions are called) in the child then a copy is made + * and subsequent changes to the corresponding member of the parent will no longer be visible in the child. + */ + PlanningScenePtr diff() const; + + /** \brief Return a new child PlanningScene that uses this one as parent and + * has the diffs specified by \e msg applied. */ + PlanningScenePtr diff(const moveit_msgs::msg::PlanningScene& msg) const; + + /** \brief Get the parent scene (with respect to which the diffs are maintained). This may be empty */ + const PlanningSceneConstPtr& getParent() const + { + return parent_; + } + + /** \brief Get the kinematic model for which the planning scene is maintained */ + const moveit::core::RobotModelConstPtr& getRobotModel() const + { + // the kinematic model does not change + return robot_model_; + } + + /** \brief Get the state at which the robot is assumed to be. */ + const moveit::core::RobotState& getCurrentState() const + { + // if we have an updated state, return it; otherwise, return the parent one + return robot_state_.has_value() ? robot_state_.value() : parent_->getCurrentState(); + } + /** \brief Get the state at which the robot is assumed to be. */ + moveit::core::RobotState& getCurrentStateNonConst(); + + /** \brief Get a copy of the current state with components overwritten by the state message \e update */ + moveit::core::RobotStatePtr getCurrentStateUpdated(const moveit_msgs::msg::RobotState& update) const; + + /** + * \name Reasoning about frames + */ + /**@{*/ + + /** \brief Get the frame in which planning is performed */ + const std::string& getPlanningFrame() const + { + // if we have an updated set of transforms, return it; otherwise, return the parent one + return scene_transforms_.has_value() ? scene_transforms_.value()->getTargetFrame() : parent_->getPlanningFrame(); + } + + /** \brief Get the set of fixed transforms from known frames to the planning frame */ + const moveit::core::Transforms& getTransforms() const + { + if (scene_transforms_.has_value() || !parent_) + { + return *scene_transforms_.value(); + } + + // if this planning scene is a child of another, and doesn't have its own custom transforms + return parent_->getTransforms(); + } + + /** \brief Get the set of fixed transforms from known frames to the planning frame. This variant is non-const and also + * updates the current state */ + const moveit::core::Transforms& getTransforms(); + + /** \brief Get the set of fixed transforms from known frames to the planning frame */ + moveit::core::Transforms& getTransformsNonConst(); + + /** \brief Get the transform corresponding to the frame \e id. This will be known if \e id is a link name, an attached + body id or a collision object. + Return identity when no transform is available. Use knowsFrameTransform() to test if this function will be + successful or not. */ + const Eigen::Isometry3d& getFrameTransform(const std::string& id) const; + + /** \brief Get the transform corresponding to the frame \e id. This will be known if \e id is a link name, an attached + body id or a collision object. + Return identity when no transform is available. Use knowsFrameTransform() to test if this function will be + successful or not. + Because this function is non-const, the current state transforms are also updated, if needed. */ + const Eigen::Isometry3d& getFrameTransform(const std::string& id); + + /** \brief Get the transform corresponding to the frame \e id. This will be known if \e id is a link name, an attached + body id or a collision object. + Return identity when no transform is available. Use knowsFrameTransform() to test if this function will be + successful or not. This function also + updates the link transforms of \e state. */ + const Eigen::Isometry3d& getFrameTransform(moveit::core::RobotState& state, const std::string& id) const + { + state.updateLinkTransforms(); + return getFrameTransform(static_cast(state), id); + } + + /** \brief Get the transform corresponding to the frame \e id. This will be known if \e id is a link name, an attached + body id or a collision object. + Return identity when no transform is available. Use knowsFrameTransform() to test if this function will be + successful or not. */ + const Eigen::Isometry3d& getFrameTransform(const moveit::core::RobotState& state, const std::string& id) const; + + /** \brief Check if a transform to the frame \e id is known. This will be known if \e id is a link name, an attached + * body id or a collision object */ + bool knowsFrameTransform(const std::string& id) const; + + /** \brief Check if a transform to the frame \e id is known. This will be known if \e id is a link name, an attached + * body id or a collision object */ + bool knowsFrameTransform(const moveit::core::RobotState& state, const std::string& id) const; + + /**@}*/ + + /** + * \name Reasoning about the geometry of the planning scene + */ + /**@{*/ + + const std::string getCollisionDetectorName() const + { + // If no collision detector is allocated, return an empty string + return collision_detector_ ? (collision_detector_->alloc_->getName()) : ""; + } + + /** \brief Get the representation of the world */ + const collision_detection::WorldConstPtr& getWorld() const + { + // we always have a world representation + return world_const_; + } + + /** \brief Get the representation of the world */ + const collision_detection::WorldPtr& getWorldNonConst() + { + // we always have a world representation + return world_; + } + + /** \brief Get the active collision environment */ + const collision_detection::CollisionEnvConstPtr& getCollisionEnv() const + { + return collision_detector_->getCollisionEnv(); + } + + /** \brief Get the active collision detector for the robot */ + const collision_detection::CollisionEnvConstPtr& getCollisionEnvUnpadded() const + { + return collision_detector_->getCollisionEnvUnpadded(); + } + + /** \brief Get a specific collision detector for the world. If not found return active CollisionWorld. */ + const collision_detection::CollisionEnvConstPtr& getCollisionEnv(const std::string& collision_detector_name) const; + + /** \brief Get a specific collision detector for the unpadded robot. If no found return active unpadded + * CollisionRobot. */ + const collision_detection::CollisionEnvConstPtr& + getCollisionEnvUnpadded(const std::string& collision_detector_name) const; + + /** \brief Get the representation of the collision robot + * This can be used to set padding and link scale on the active collision_robot. */ + const collision_detection::CollisionEnvPtr& getCollisionEnvNonConst(); + + /** \brief Get the allowed collision matrix */ + const collision_detection::AllowedCollisionMatrix& getAllowedCollisionMatrix() const + { + return acm_.has_value() ? acm_.value() : parent_->getAllowedCollisionMatrix(); + } + + /** \brief Get the allowed collision matrix */ + collision_detection::AllowedCollisionMatrix& getAllowedCollisionMatrixNonConst(); + + /** \brief Set the allowed collision matrix */ + void setAllowedCollisionMatrix(const collision_detection::AllowedCollisionMatrix& acm); + + /**@}*/ + + /** + * \name Collision checking with respect to this planning scene + */ + /**@{*/ + + /** \brief Check if the current state is in collision (with the environment or self collision). + If a group name is specified, collision checking is done for that group only (plus descendent links). + Since the function is non-const, the current state transforms are updated before the collision check. */ + bool isStateColliding(const std::string& group = "", bool verbose = false); + + /** \brief Check if the current state is in collision (with the environment or self collision). If a group name is + specified, + collision checking is done for that group only (plus descendent links). It is expected the current state + transforms are up to date. */ + bool isStateColliding(const std::string& group = "", bool verbose = false) const + { + return isStateColliding(getCurrentState(), group, verbose); + } + + /** \brief Check if a given state is in collision (with the environment or self collision) If a group name is + specified, + collision checking is done for that group only (plus descendent links). The link transforms for \e state are + updated before the collision check. */ + bool isStateColliding(moveit::core::RobotState& state, const std::string& group = "", bool verbose = false) const + { + state.updateCollisionBodyTransforms(); + return isStateColliding(static_cast(state), group, verbose); + } + + /** \brief Check if a given state is in collision (with the environment or self collision) + If a group name is specified, collision checking is done for that group only (plus descendent links). It is + expected that the link transforms of \e state are up to date. */ + bool isStateColliding(const moveit::core::RobotState& state, const std::string& group = "", + bool verbose = false) const; + + /** \brief Check if a given state is in collision (with the environment or self collision) + If a group name is specified, collision checking is done for that group only (plus descendent links). */ + bool isStateColliding(const moveit_msgs::msg::RobotState& state, const std::string& group = "", + bool verbose = false) const; + + /** \brief Check whether the current state is in collision, and if needed, updates the collision transforms of the + * current state before the computation. */ + void checkCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res); + + /** \brief Check whether the current state is in collision. The current state is expected to be updated. */ + void checkCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res) const; + + /** \brief Check whether a specified state (\e robot_state) is in collision. This variant of the function takes + a non-const \e robot_state and calls updateCollisionBodyTransforms() on it. */ + void checkCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, + moveit::core::RobotState& robot_state) const; + + /** \brief Check whether a specified state (\e robot_state) is in collision. The collision transforms of \e + * robot_state are + * expected to be up to date. */ + void checkCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, + const moveit::core::RobotState& robot_state) const; + + /** \brief Check whether a specified state (\e robot_state) is in collision, with respect to a given + allowed collision matrix (\e acm). This variant of the function takes + a non-const \e robot_state and updates its link transforms if needed. */ + void checkCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, + moveit::core::RobotState& robot_state, + const collision_detection::AllowedCollisionMatrix& acm) const; + + /** \brief Check whether a specified state (\e robot_state) is in collision, with respect to a given + allowed collision matrix (\e acm). */ + void checkCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, + const moveit::core::RobotState& robot_state, + const collision_detection::AllowedCollisionMatrix& acm) const; + + /** \brief Check whether the current state is in collision, + but use a collision_detection::CollisionRobot instance that has no padding. + Since the function is non-const, the current state transforms are also updated if needed. */ + [[deprecated("Use new CollisionRequest flags to enable/ disable padding instead.")]] void + checkCollisionUnpadded(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res); + + /** \brief Check whether the current state is in collision, + but use a collision_detection::CollisionRobot instance that has no padding. */ + [[deprecated("Use new CollisionRequest flags to enable/ disable padding instead.")]] void + checkCollisionUnpadded(const collision_detection::CollisionRequest& req, + collision_detection::CollisionResult& res) const; + + /** \brief Check whether a specified state (\e robot_state) is in collision, + but use a collision_detection::CollisionRobot instance that has no padding. */ + [[deprecated("Use new CollisionRequest flags to enable/ disable padding instead.")]] void + checkCollisionUnpadded(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, + const moveit::core::RobotState& robot_state) const; + + /** \brief Check whether a specified state (\e robot_state) is in collision, + but use a collision_detection::CollisionRobot instance that has no padding. + Update the link transforms of \e robot_state if needed. */ + [[deprecated("Use new CollisionRequest flags to enable/ disable padding instead.")]] void + checkCollisionUnpadded(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, + moveit::core::RobotState& robot_state) const; + + /** \brief Check whether a specified state (\e robot_state) is in collision, with respect to a given + allowed collision matrix (\e acm), but use a collision_detection::CollisionRobot instance that has no padding. + This variant of the function takes a non-const \e robot_state and calls updates the link transforms if needed. */ + [[deprecated("Use new CollisionRequest flags to enable/ disable padding instead.")]] void + checkCollisionUnpadded(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, + moveit::core::RobotState& robot_state, + const collision_detection::AllowedCollisionMatrix& acm) const; + + /** \brief Check whether a specified state (\e robot_state) is in collision, with respect to a given + allowed collision matrix (\e acm), but use a collision_detection::CollisionRobot instance that has no padding. */ + [[deprecated("Use new CollisionRequest flags to enable/ disable padding instead.")]] void + checkCollisionUnpadded(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, + const moveit::core::RobotState& robot_state, + const collision_detection::AllowedCollisionMatrix& acm) const; + + /** \brief Check whether the current state is in self collision */ + void checkSelfCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res); + + /** \brief Check whether the current state is in self collision */ + void checkSelfCollision(const collision_detection::CollisionRequest& req, + collision_detection::CollisionResult& res) const; + + /** \brief Check whether a specified state (\e robot_state) is in self collision */ + void checkSelfCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, + moveit::core::RobotState& robot_state) const; + + /** \brief Check whether a specified state (\e robot_state) is in self collision */ + void checkSelfCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, + const moveit::core::RobotState& robot_state) const; + + /** \brief Check whether a specified state (\e robot_state) is in self collision, with respect to a given + allowed collision matrix (\e acm). The link transforms of \e robot_state are updated if needed. */ + void checkSelfCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, + moveit::core::RobotState& robot_state, + const collision_detection::AllowedCollisionMatrix& acm) const; + + /** \brief Check whether a specified state (\e robot_state) is in self collision, with respect to a given + allowed collision matrix (\e acm) */ + void checkSelfCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, + const moveit::core::RobotState& robot_state, + const collision_detection::AllowedCollisionMatrix& acm) const; + + /** \brief Get the names of the links that are involved in collisions for the current state */ + void getCollidingLinks(std::vector& links); + + /** \brief Get the names of the links that are involved in collisions for the current state */ + void getCollidingLinks(std::vector& links) const + { + getCollidingLinks(links, getCurrentState(), getAllowedCollisionMatrix()); + } + + /** \brief Get the names of the links that are involved in collisions for the state \e robot_state. + Update the link transforms for \e robot_state if needed. */ + void getCollidingLinks(std::vector& links, moveit::core::RobotState& robot_state) const + { + robot_state.updateCollisionBodyTransforms(); + getCollidingLinks(links, static_cast(robot_state), getAllowedCollisionMatrix()); + } + + /** \brief Get the names of the links that are involved in collisions for the state \e robot_state */ + void getCollidingLinks(std::vector& links, const moveit::core::RobotState& robot_state) const + { + getCollidingLinks(links, robot_state, getAllowedCollisionMatrix()); + } + + /** \brief Get the names of the links that are involved in collisions for the state \e robot_state given the + allowed collision matrix (\e acm) */ + void getCollidingLinks(std::vector& links, moveit::core::RobotState& robot_state, + const collision_detection::AllowedCollisionMatrix& acm) const + { + robot_state.updateCollisionBodyTransforms(); + getCollidingLinks(links, static_cast(robot_state), acm); + } + + /** \brief Get the names of the links that are involved in collisions for the state \e robot_state given the + allowed collision matrix (\e acm) */ + void getCollidingLinks(std::vector& links, const moveit::core::RobotState& robot_state, + const collision_detection::AllowedCollisionMatrix& acm) const; + + /** \brief Get the names of the links that are involved in collisions for the current state. + Update the link transforms for the current state if needed. */ + void getCollidingPairs(collision_detection::CollisionResult::ContactMap& contacts); + + /** \brief Get the names of the links that are involved in collisions for the current state */ + void getCollidingPairs(collision_detection::CollisionResult::ContactMap& contacts) const + { + getCollidingPairs(contacts, getCurrentState(), getAllowedCollisionMatrix()); + } + + /** \brief Get the names of the links that are involved in collisions for the state \e robot_state. + * Can be restricted to links part of or updated by \e group_name (plus descendent links) */ + void getCollidingPairs(collision_detection::CollisionResult::ContactMap& contacts, + const moveit::core::RobotState& robot_state, const std::string& group_name = "") const + { + getCollidingPairs(contacts, robot_state, getAllowedCollisionMatrix(), group_name); + } + + /** \brief Get the names of the links that are involved in collisions for the state \e robot_state. + Update the link transforms for \e robot_state if needed. + Can be restricted to links part of or updated by \e group_name (plus descendent links) */ + void getCollidingPairs(collision_detection::CollisionResult::ContactMap& contacts, + moveit::core::RobotState& robot_state, const std::string& group_name = "") const + { + robot_state.updateCollisionBodyTransforms(); + getCollidingPairs(contacts, static_cast(robot_state), getAllowedCollisionMatrix(), + group_name); + } + + /** \brief Get the names of the links that are involved in collisions for the state \e robot_state given the + allowed collision matrix (\e acm). Update the link transforms for \e robot_state if needed. + Can be restricted to links part of or updated by \e group_name (plus descendent links) */ + void getCollidingPairs(collision_detection::CollisionResult::ContactMap& contacts, + moveit::core::RobotState& robot_state, const collision_detection::AllowedCollisionMatrix& acm, + const std::string& group_name = "") const + { + robot_state.updateCollisionBodyTransforms(); + getCollidingPairs(contacts, static_cast(robot_state), acm, group_name); + } + + /** \brief Get the names of the links that are involved in collisions for the state \e robot_state given the + allowed collision matrix (\e acm). Can be restricted to links part of or updated by \e group_name (plus descendent links) */ + void getCollidingPairs(collision_detection::CollisionResult::ContactMap& contacts, + const moveit::core::RobotState& robot_state, + const collision_detection::AllowedCollisionMatrix& acm, + const std::string& group_name = "") const; + + /**@}*/ + + /** + * \name Distance computation + */ + /**@{*/ + + /** \brief The distance between the robot model at state \e robot_state to the nearest collision (ignoring + * self-collisions) + */ + double distanceToCollision(moveit::core::RobotState& robot_state) const + { + robot_state.updateCollisionBodyTransforms(); + return distanceToCollision(static_cast(robot_state)); + } + + /** \brief The distance between the robot model at state \e robot_state to the nearest collision (ignoring + * self-collisions) + */ + double distanceToCollision(const moveit::core::RobotState& robot_state) const + { + return getCollisionEnv()->distanceRobot(robot_state, getAllowedCollisionMatrix()); + } + + /** \brief The distance between the robot model at state \e robot_state to the nearest collision (ignoring + * self-collisions), if the robot has no padding */ + double distanceToCollisionUnpadded(moveit::core::RobotState& robot_state) const + { + robot_state.updateCollisionBodyTransforms(); + return distanceToCollisionUnpadded(static_cast(robot_state)); + } + + /** \brief The distance between the robot model at state \e robot_state to the nearest collision (ignoring + * self-collisions), if the robot has no padding */ + double distanceToCollisionUnpadded(const moveit::core::RobotState& robot_state) const + { + return getCollisionEnvUnpadded()->distanceRobot(robot_state, getAllowedCollisionMatrix()); + } + + /** \brief The distance between the robot model at state \e robot_state to the nearest collision, ignoring + * self-collisions + * and elements that are allowed to collide. */ + double distanceToCollision(moveit::core::RobotState& robot_state, + const collision_detection::AllowedCollisionMatrix& acm) const + { + robot_state.updateCollisionBodyTransforms(); + return distanceToCollision(static_cast(robot_state), acm); + } + + /** \brief The distance between the robot model at state \e robot_state to the nearest collision, ignoring + * self-collisions + * and elements that are allowed to collide. */ + double distanceToCollision(const moveit::core::RobotState& robot_state, + const collision_detection::AllowedCollisionMatrix& acm) const + { + return getCollisionEnv()->distanceRobot(robot_state, acm); + } + + /** \brief The distance between the robot model at state \e robot_state to the nearest collision, ignoring + * self-collisions + * and elements that are allowed to collide, if the robot has no padding. */ + double distanceToCollisionUnpadded(moveit::core::RobotState& robot_state, + const collision_detection::AllowedCollisionMatrix& acm) const + { + robot_state.updateCollisionBodyTransforms(); + return distanceToCollisionUnpadded(static_cast(robot_state), acm); + } + + /** \brief The distance between the robot model at state \e robot_state to the nearest collision, ignoring + * self-collisions + * and elements that always allowed to collide, if the robot has no padding. */ + double distanceToCollisionUnpadded(const moveit::core::RobotState& robot_state, + const collision_detection::AllowedCollisionMatrix& acm) const + { + return getCollisionEnvUnpadded()->distanceRobot(robot_state, acm); + } + + /**@}*/ + + /** \brief Save the geometry of the planning scene to a stream, as plain text */ + void saveGeometryToStream(std::ostream& out) const; + + /** \brief Load the geometry of the planning scene from a stream */ + bool loadGeometryFromStream(std::istream& in); + + /** \brief Load the geometry of the planning scene from a stream at a certain location using offset*/ + bool loadGeometryFromStream(std::istream& in, const Eigen::Isometry3d& offset); + + /** \brief Fill the message \e scene with the differences between this instance of PlanningScene with respect to the + parent. + If there is no parent, everything is considered to be a diff and the function behaves like getPlanningSceneMsg() + */ + void getPlanningSceneDiffMsg(moveit_msgs::msg::PlanningScene& scene) const; + + /** \brief Construct a message (\e scene) with all the necessary data so that the scene can be later reconstructed to + be + exactly the same using setPlanningSceneMsg() */ + void getPlanningSceneMsg(moveit_msgs::msg::PlanningScene& scene) const; + + /** \brief Construct a message (\e scene) with the data requested in \e comp. If all options in \e comp are filled, + this will be a complete planning scene message */ + void getPlanningSceneMsg(moveit_msgs::msg::PlanningScene& scene, + const moveit_msgs::msg::PlanningSceneComponents& comp) const; + + /** \brief Construct a message (\e collision_object) with the collision object data from the planning_scene for the + * requested object*/ + bool getCollisionObjectMsg(moveit_msgs::msg::CollisionObject& collision_obj, const std::string& ns) const; + + /** \brief Construct a vector of messages (\e collision_objects) with the collision object data for all objects in + * planning_scene */ + void getCollisionObjectMsgs(std::vector& collision_objs) const; + + /** \brief Construct a message (\e attached_collision_object) with the attached collision object data from the + * planning_scene for the requested object*/ + bool getAttachedCollisionObjectMsg(moveit_msgs::msg::AttachedCollisionObject& attached_collision_obj, + const std::string& ns) const; + + /** \brief Construct a vector of messages (\e attached_collision_objects) with the attached collision object data for + * all objects in planning_scene */ + void + getAttachedCollisionObjectMsgs(std::vector& attached_collision_objs) const; + + /** \brief Construct a message (\e octomap) with the octomap data from the planning_scene */ + bool getOctomapMsg(octomap_msgs::msg::OctomapWithPose& octomap) const; + + /** \brief Construct a vector of messages (\e object_colors) with the colors of the objects from the planning_scene */ + void getObjectColorMsgs(std::vector& object_colors) const; + + /** \brief Apply changes to this planning scene as diffs, even if the message itself is not marked as being a diff + (is_diff + member). A parent is not required to exist. However, the existing data in the planning instance is not cleared. + Data from + the message is only appended (and in cases such as e.g., the robot state, is overwritten). */ + bool setPlanningSceneDiffMsg(const moveit_msgs::msg::PlanningScene& scene); + + /** \brief Set this instance of a planning scene to be the same as the one serialized in the \e scene message, even if + * the message itself is marked as being a diff (is_diff member) */ + bool setPlanningSceneMsg(const moveit_msgs::msg::PlanningScene& scene); + + /** \brief Call setPlanningSceneMsg() or setPlanningSceneDiffMsg() depending on how the is_diff member of the message + * is set */ + bool usePlanningSceneMsg(const moveit_msgs::msg::PlanningScene& scene); + + /** \brief Takes the object message and returns the object pose, shapes and shape poses. + * If the object pose is empty (identity) but the shape pose is set, this uses the shape + * pose as the object pose. The shape pose becomes the identity instead. + */ + bool shapesAndPosesFromCollisionObjectMessage(const moveit_msgs::msg::CollisionObject& object, + Eigen::Isometry3d& object_pose_in_header_frame, + std::vector& shapes, + EigenSTL::vector_Isometry3d& shape_poses); + + bool processCollisionObjectMsg(const moveit_msgs::msg::CollisionObject& object); + bool processAttachedCollisionObjectMsg(const moveit_msgs::msg::AttachedCollisionObject& object); + + bool processPlanningSceneWorldMsg(const moveit_msgs::msg::PlanningSceneWorld& world); + + void processOctomapMsg(const octomap_msgs::msg::OctomapWithPose& map); + void processOctomapMsg(const octomap_msgs::msg::Octomap& map); + void processOctomapPtr(const std::shared_ptr& octree, const Eigen::Isometry3d& t); + + /** + * \brief Clear all collision objects in planning scene + */ + void removeAllCollisionObjects(); + + /** \brief Set the current robot state to be \e state. If not + all joint values are specified, the previously maintained + joint values are kept. */ + void setCurrentState(const moveit_msgs::msg::RobotState& state); + + /** \brief Set the current robot state */ + void setCurrentState(const moveit::core::RobotState& state); + + /** \brief Set the callback to be triggered when changes are made to the current scene state */ + void setAttachedBodyUpdateCallback(const moveit::core::AttachedBodyCallback& callback); + + /** \brief Set the callback to be triggered when changes are made to the current scene world */ + void setCollisionObjectUpdateCallback(const collision_detection::World::ObserverCallbackFn& callback); + + bool hasObjectColor(const std::string& id) const; + + /** + * \brief Gets the current color of an object. + * \param id The string id of the target object. + * \return The current object color. + */ + const std_msgs::msg::ColorRGBA& getObjectColor(const std::string& id) const; + + /** + * \brief Tries to get the original color of an object, if one has been set before. + * \param id The string id of the target object. + * \return The original object color, if available, otherwise std::nullopt. + */ + std::optional getOriginalObjectColor(const std::string& id) const; + + void setObjectColor(const std::string& id, const std_msgs::msg::ColorRGBA& color); + void removeObjectColor(const std::string& id); + void getKnownObjectColors(ObjectColorMap& kc) const; + + bool hasObjectType(const std::string& id) const; + + const object_recognition_msgs::msg::ObjectType& getObjectType(const std::string& id) const; + void setObjectType(const std::string& id, const object_recognition_msgs::msg::ObjectType& type); + void removeObjectType(const std::string& id); + void getKnownObjectTypes(ObjectTypeMap& kc) const; + + /** \brief Clear the diffs accumulated for this planning scene, with respect to: + * the parent PlanningScene (if it exists) + * the parent CollisionDetector (if it exists) + * This function is a no-op if there is no parent planning scene. */ + void clearDiffs(); + + /** \brief If there is a parent specified for this scene, then the diffs with respect to that parent are applied to a + specified planning scene, whatever + that scene may be. If there is no parent specified, this function is a no-op. */ + void pushDiffs(const PlanningScenePtr& scene); + + /** \brief Make sure that all the data maintained in this + scene is local. All unmodified data is copied from the + parent and the pointer to the parent is discarded. */ + void decoupleParent(); + + /** \brief Specify a predicate that decides whether states are considered valid or invalid for reasons beyond ones + covered by collision checking and constraint evaluation. + This is useful for setting up problem specific constraints (e.g., stability) */ + void setStateFeasibilityPredicate(const StateFeasibilityFn& fn) + { + state_feasibility_ = fn; + } + + /** \brief Get the predicate that decides whether states are considered valid or invalid for reasons beyond ones + * covered by collision checking and constraint evaluation. */ + const StateFeasibilityFn& getStateFeasibilityPredicate() const + { + return state_feasibility_; + } + + /** \brief Specify a predicate that decides whether motion segments are considered valid or invalid for reasons beyond + * ones covered by collision checking and constraint evaluation. */ + void setMotionFeasibilityPredicate(const MotionFeasibilityFn& fn) + { + motion_feasibility_ = fn; + } + + /** \brief Get the predicate that decides whether motion segments are considered valid or invalid for reasons beyond + * ones covered by collision checking and constraint evaluation. */ + const MotionFeasibilityFn& getMotionFeasibilityPredicate() const + { + return motion_feasibility_; + } + + /** \brief Check if a given state is feasible, in accordance to the feasibility predicate specified by + * setStateFeasibilityPredicate(). Returns true if no feasibility predicate was specified. */ + bool isStateFeasible(const moveit_msgs::msg::RobotState& state, bool verbose = false) const; + + /** \brief Check if a given state is feasible, in accordance to the feasibility predicate specified by + * setStateFeasibilityPredicate(). Returns true if no feasibility predicate was specified. */ + bool isStateFeasible(const moveit::core::RobotState& state, bool verbose = false) const; + + /** \brief Check if a given state satisfies a set of constraints */ + bool isStateConstrained(const moveit_msgs::msg::RobotState& state, const moveit_msgs::msg::Constraints& constr, + bool verbose = false) const; + + /** \brief Check if a given state satisfies a set of constraints */ + bool isStateConstrained(const moveit::core::RobotState& state, const moveit_msgs::msg::Constraints& constr, + bool verbose = false) const; + + /** \brief Check if a given state satisfies a set of constraints */ + bool isStateConstrained(const moveit_msgs::msg::RobotState& state, + const kinematic_constraints::KinematicConstraintSet& constr, bool verbose = false) const; + + /** \brief Check if a given state satisfies a set of constraints */ + bool isStateConstrained(const moveit::core::RobotState& state, + const kinematic_constraints::KinematicConstraintSet& constr, bool verbose = false) const; + + /** \brief Check if a given state is valid. This means checking for collisions and feasibility. Includes descendent + * links of \e group. */ + bool isStateValid(const moveit_msgs::msg::RobotState& state, const std::string& group = "", + bool verbose = false) const; + + /** \brief Check if a given state is valid. This means checking for collisions and feasibility. Includes descendent + * links of \e group. */ + bool isStateValid(const moveit::core::RobotState& state, const std::string& group = "", bool verbose = false) const; + + /** \brief Check if a given state is valid. This means checking for collisions, feasibility and whether the user + * specified validity conditions hold as well. Includes descendent links of \e group. */ + bool isStateValid(const moveit_msgs::msg::RobotState& state, const moveit_msgs::msg::Constraints& constr, + const std::string& group = "", bool verbose = false) const; + + /** \brief Check if a given state is valid. This means checking for collisions, feasibility and whether the user + * specified validity conditions hold as well. Includes descendent links of \e group. */ + bool isStateValid(const moveit::core::RobotState& state, const moveit_msgs::msg::Constraints& constr, + const std::string& group = "", bool verbose = false) const; + + /** \brief Check if a given state is valid. This means checking for collisions, feasibility and whether the user + * specified validity conditions hold as well. Includes descendent links of \e group. */ + bool isStateValid(const moveit::core::RobotState& state, const kinematic_constraints::KinematicConstraintSet& constr, + const std::string& group = "", bool verbose = false) const; + + /** \brief Check if a given path is valid. Each state is checked for validity (collision avoidance and feasibility). + * Includes descendent links of \e group. */ + bool isPathValid(const moveit_msgs::msg::RobotState& start_state, const moveit_msgs::msg::RobotTrajectory& trajectory, + const std::string& group = "", bool verbose = false, + std::vector* invalid_index = nullptr) const; + + /** \brief Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and + * constraint satisfaction). It is also checked that the goal constraints are satisfied by the last state on the + * passed in trajectory. Includes descendent links of \e group. */ + bool isPathValid(const moveit_msgs::msg::RobotState& start_state, const moveit_msgs::msg::RobotTrajectory& trajectory, + const moveit_msgs::msg::Constraints& path_constraints, const std::string& group = "", + bool verbose = false, std::vector* invalid_index = nullptr) const; + + /** \brief Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and + * constraint satisfaction). It is also checked that the goal constraints are satisfied by the last state on the + * passed in trajectory. Includes descendent links of \e group. */ + bool isPathValid(const moveit_msgs::msg::RobotState& start_state, const moveit_msgs::msg::RobotTrajectory& trajectory, + const moveit_msgs::msg::Constraints& path_constraints, + const moveit_msgs::msg::Constraints& goal_constraints, const std::string& group = "", + bool verbose = false, std::vector* invalid_index = nullptr) const; + + /** \brief Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and + * constraint satisfaction). It is also checked that the goal constraints are satisfied by the last state on the + * passed in trajectory. Includes descendent links of \e group. */ + bool isPathValid(const moveit_msgs::msg::RobotState& start_state, const moveit_msgs::msg::RobotTrajectory& trajectory, + const moveit_msgs::msg::Constraints& path_constraints, + const std::vector& goal_constraints, const std::string& group = "", + bool verbose = false, std::vector* invalid_index = nullptr) const; + + /** \brief Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and + * constraint satisfaction). It is also checked that the goal constraints are satisfied by the last state on the + * passed in trajectory. Includes descendent links of \e group. */ + bool isPathValid(const robot_trajectory::RobotTrajectory& trajectory, + const moveit_msgs::msg::Constraints& path_constraints, + const std::vector& goal_constraints, const std::string& group = "", + bool verbose = false, std::vector* invalid_index = nullptr) const; + + /** \brief Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and + * constraint satisfaction). It is also checked that the goal constraints are satisfied by the last state on the + * passed in trajectory. Includes descendent links of \e group. */ + bool isPathValid(const robot_trajectory::RobotTrajectory& trajectory, + const moveit_msgs::msg::Constraints& path_constraints, + const moveit_msgs::msg::Constraints& goal_constraints, const std::string& group = "", + bool verbose = false, std::vector* invalid_index = nullptr) const; + + /** \brief Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and + * constraint satisfaction). Includes descendent links of \e group. */ + bool isPathValid(const robot_trajectory::RobotTrajectory& trajectory, + const moveit_msgs::msg::Constraints& path_constraints, const std::string& group = "", + bool verbose = false, std::vector* invalid_index = nullptr) const; + + /** \brief Check if a given path is valid. Each state is checked for validity (collision avoidance and feasibility). + * Includes descendent links of \e group. */ + bool isPathValid(const robot_trajectory::RobotTrajectory& trajectory, const std::string& group = "", + bool verbose = false, std::vector* invalid_index = nullptr) const; + + /** \brief Get the top \e max_costs cost sources for a specified trajectory. The resulting costs are stored in \e + * costs */ + void getCostSources(const robot_trajectory::RobotTrajectory& trajectory, std::size_t max_costs, + std::set& costs, double overlap_fraction = 0.9) const; + + /** \brief Get the top \e max_costs cost sources for a specified trajectory, but only for group \e group_name (plus + * descendent links). The resulting costs are stored in \e costs */ + void getCostSources(const robot_trajectory::RobotTrajectory& trajectory, std::size_t max_costs, + const std::string& group_name, std::set& costs, + double overlap_fraction = 0.9) const; + + /** \brief Get the top \e max_costs cost sources for a specified state. The resulting costs are stored in \e costs */ + void getCostSources(const moveit::core::RobotState& state, std::size_t max_costs, + std::set& costs) const; + + /** \brief Get the top \e max_costs cost sources for a specified state, but only for group \e group_name (plus + * descendent links). The resulting costs are stored in \e costs */ + void getCostSources(const moveit::core::RobotState& state, std::size_t max_costs, const std::string& group_name, + std::set& costs) const; + + /** \brief Outputs debug information about the planning scene contents */ + void printKnownObjects(std::ostream& out = std::cout) const; + + /** \brief Clone a planning scene. Even if the scene \e scene depends on a parent, the cloned scene will not. */ + static PlanningScenePtr clone(const PlanningSceneConstPtr& scene); + + /** \brief Allocate a new collision detector and replace the previous one if there was any. + * + * The collision detector type is specified with (a shared pointer to) an + * allocator which is a subclass of CollisionDetectorAllocator. This + * identifies a combination of CollisionWorld/CollisionRobot which can be + * used together. + * + * A new PlanningScene uses an FCL collision detector by default. + * + * example: to add FCL collision detection (normally not necessary) call + * planning_scene->allocateCollisionDetector(collision_detection::CollisionDetectorAllocatorFCL::create()); + * + * */ + void allocateCollisionDetector(const collision_detection::CollisionDetectorAllocatorPtr& allocator) + { + allocateCollisionDetector(allocator, nullptr /* no parent_detector */); + } + +private: + /* Private constructor used by the diff() methods. */ + PlanningScene(const PlanningSceneConstPtr& parent); + + /* Initialize the scene. This should only be called by the constructors. + * Requires a valid robot_model_ */ + void initialize(); + + /* Helper functions for processing collision objects */ + bool processCollisionObjectAdd(const moveit_msgs::msg::CollisionObject& object); + bool processCollisionObjectRemove(const moveit_msgs::msg::CollisionObject& object); + bool processCollisionObjectMove(const moveit_msgs::msg::CollisionObject& object); + + MOVEIT_STRUCT_FORWARD(CollisionDetector); + + /* Construct a new CollisionDector from allocator, copy-construct environments from parent_detector if not nullptr */ + void allocateCollisionDetector(const collision_detection::CollisionDetectorAllocatorPtr& allocator, + const CollisionDetectorPtr& parent_detector); + + /* \brief A set of compatible collision detectors */ + struct CollisionDetector + { + collision_detection::CollisionDetectorAllocatorPtr alloc_; + collision_detection::CollisionEnvPtr cenv_; // never nullptr + collision_detection::CollisionEnvConstPtr cenv_const_; + + collision_detection::CollisionEnvPtr cenv_unpadded_; + collision_detection::CollisionEnvConstPtr cenv_unpadded_const_; + + const collision_detection::CollisionEnvConstPtr& getCollisionEnv() const + { + return cenv_const_; + } + const collision_detection::CollisionEnvConstPtr& getCollisionEnvUnpadded() const + { + return cenv_unpadded_const_; + } + void copyPadding(const CollisionDetector& src); + }; + friend struct CollisionDetector; + + std::string name_; // may be empty + + PlanningSceneConstPtr parent_; // Null unless this is a diff scene + + moveit::core::RobotModelConstPtr robot_model_; // Never null (may point to same model as parent) + + std::optional robot_state_; // if there is no value use parent's + + // Called when changes are made to attached bodies + moveit::core::AttachedBodyCallback current_state_attached_body_callback_; + + // This variable is not necessarily used by child planning scenes + // This Transforms class is actually a SceneTransforms class + std::optional scene_transforms_; // if there is no value use parent's + + collision_detection::WorldPtr world_; // never nullptr, never shared with parent/child + collision_detection::WorldConstPtr world_const_; // copy of world_ + collision_detection::WorldDiffPtr world_diff_; // nullptr unless this is a diff scene + collision_detection::World::ObserverCallbackFn current_world_object_update_callback_; + collision_detection::World::ObserverHandle current_world_object_update_observer_handle_; + + CollisionDetectorPtr collision_detector_; // Never nullptr. + + std::optional acm_; // if there is no value use parent's + + StateFeasibilityFn state_feasibility_; + MotionFeasibilityFn motion_feasibility_; + + // Maps of current and original object colors (to manage attaching/detaching objects) + std::unique_ptr object_colors_; + std::unique_ptr original_object_colors_; + + // a map of object types + std::optional object_types_; +}; +} // namespace planning_scene From 695d1c7a282ed057556098bdd58f8183391d7603 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Mon, 18 Nov 2024 20:32:33 +0000 Subject: [PATCH 26/53] Fixes merge conflicts --- .../collision_detection/collision_common.h | 371 ------ .../collision_detection/collision_common.hpp | 6 + .../moveit/planning_scene/planning_scene.h | 1003 ----------------- .../moveit/planning_scene/planning_scene.hpp | 95 +- 4 files changed, 33 insertions(+), 1442 deletions(-) delete mode 100644 moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h delete mode 100644 moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h deleted file mode 100644 index 0fcd4f9808..0000000000 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h +++ /dev/null @@ -1,371 +0,0 @@ -/********************************************************************* - * Software License Agreement (BSD License) - * - * Copyright (c) 2011, Willow Garage, Inc. - * 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 Willow Garage 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. - *********************************************************************/ - -/* Author: Ioan Sucan */ - -#pragma once - -#include -#include -#include -#include -#include -#include -#include -#include - -namespace collision_detection -{ -MOVEIT_CLASS_FORWARD(AllowedCollisionMatrix); // Defines AllowedCollisionMatrixPtr, ConstPtr, WeakPtr... etc - -/** \brief The types of bodies that are considered for collision */ -namespace BodyTypes -{ -/** \brief The types of bodies that are considered for collision */ -enum Type -{ - /** \brief A link on the robot */ - ROBOT_LINK, - - /** \brief A body attached to a robot link */ - ROBOT_ATTACHED, - - /** \brief A body in the environment */ - WORLD_OBJECT -}; -} // namespace BodyTypes - -/** \brief The types of bodies that are considered for collision */ -using BodyType = BodyTypes::Type; - -/** \brief Definition of a contact point */ -struct Contact -{ - EIGEN_MAKE_ALIGNED_OPERATOR_NEW - - /** \brief contact position */ - Eigen::Vector3d pos; - - /** \brief normal unit vector at contact */ - Eigen::Vector3d normal; - - /** \brief depth (penetration between bodies) */ - double depth = 0.0; - - /** \brief The id of the first body involved in the contact */ - std::string body_name_1; - - /** \brief The type of the first body involved in the contact */ - BodyType body_type_1; - - /** \brief The id of the second body involved in the contact */ - std::string body_name_2; - - /** \brief The type of the second body involved in the contact */ - BodyType body_type_2; - - /** \brief The distance percentage between casted poses until collision. - * - * If the value is 0, then the collision occurred in the start pose. If the value is 1, then the collision occurred - * in the end pose. */ - double percent_interpolation = 0.0; - - /** \brief The two nearest points connecting the two bodies */ - Eigen::Vector3d nearest_points[2]; -}; - -/** \brief When collision costs are computed, this structure contains information about the partial cost incurred in a - * particular volume */ -struct CostSource -{ - /// The minimum bound of the AABB defining the volume responsible for this partial cost - std::array aabb_min; - - /// The maximum bound of the AABB defining the volume responsible for this partial cost - std::array aabb_max; - - /// The partial cost (the probability of existence for the object there is a collision with) - double cost = 0.0; - - /// Get the volume of the AABB around the cost source - double getVolume() const - { - return (aabb_max[0] - aabb_min[0]) * (aabb_max[1] - aabb_min[1]) * (aabb_max[2] - aabb_min[2]); - } - - /// Order cost sources so that the most costly source is at the top - bool operator<(const CostSource& other) const - { - double c1 = cost * getVolume(); - double c2 = other.cost * other.getVolume(); - if (c1 > c2) - return true; - if (c1 < c2) - return false; - if (cost < other.cost) - return false; - if (cost > other.cost) - return true; - return aabb_min < other.aabb_min; - } -}; - -struct CollisionResult; - -/** \brief Representation of a collision checking request */ -struct CollisionRequest -{ - /** \brief The group name to check collisions for (optional; if empty, assume the complete robot). Descendent links - * are included. */ - std::string group_name = ""; - - /** \brief If true, use padded collision environment */ - bool pad_environment_collisions = true; - - /** \brief If true, do self collision check with padded robot links */ - bool pad_self_collisions = false; - - /** \brief If true, compute proximity distance */ - bool distance = false; - - /** \brief If true, return detailed distance information. Distance must be set to true as well */ - bool detailed_distance = false; - - /** \brief If true, a collision cost is computed */ - bool cost = false; - - /** \brief If true, compute contacts. Otherwise only a binary collision yes/no is reported. */ - bool contacts = false; - - /** \brief Overall maximum number of contacts to compute */ - std::size_t max_contacts = 1; - - /** \brief Maximum number of contacts to compute per pair of bodies (multiple bodies may be in contact at different - * configurations) */ - std::size_t max_contacts_per_pair = 1; - - /** \brief When costs are computed, this value defines how many of the top cost sources should be returned */ - std::size_t max_cost_sources = 1; - - /** \brief Function call that decides whether collision detection should stop. */ - std::function is_done = nullptr; - - /** \brief Flag indicating whether information about detected collisions should be reported */ - bool verbose = false; -}; - -namespace DistanceRequestTypes -{ -enum DistanceRequestType -{ - GLOBAL, ///< Find the global minimum - SINGLE, ///< Find the global minimum for each pair - LIMITED, ///< Find a limited(max_contacts_per_body) set of contacts for a given pair - ALL ///< Find all the contacts for a given pair -}; -} -using DistanceRequestType = DistanceRequestTypes::DistanceRequestType; - -/** \brief Representation of a distance-reporting request */ -struct DistanceRequest -{ - /*** \brief Compute \e active_components_only_ based on \e req_. This - includes links that are in the kinematic model but outside this group, if those links are descendants of - joints in this group that have their values updated. */ - void enableGroup(const moveit::core::RobotModelConstPtr& robot_model) - { - if (robot_model->hasJointModelGroup(group_name)) - { - active_components_only = &robot_model->getJointModelGroup(group_name)->getUpdatedLinkModelsSet(); - } - else - { - active_components_only = nullptr; - } - } - - /// Indicate if nearest point information should be calculated - bool enable_nearest_points = false; - - /// Indicate if a signed distance should be calculated in a collision. - bool enable_signed_distance = false; - - /// Indicate the type of distance request. If using type=ALL, it is - /// recommended to set max_contacts_per_body to the expected number - /// of contacts per pair because it is used to reserve space. - DistanceRequestType type = DistanceRequestType::GLOBAL; - - /// Maximum number of contacts to store for bodies (multiple bodies may be within distance threshold) - std::size_t max_contacts_per_body = 1; - - /// The group name - std::string group_name = ""; - - /// The set of active components to check - const std::set* active_components_only = nullptr; - - /// The allowed collision matrix used to filter checks - const AllowedCollisionMatrix* acm = nullptr; - - /// Only calculate distances for objects within this threshold to each other. - /// If set, this can significantly reduce the number of queries. - double distance_threshold = std::numeric_limits::max(); - - /// Log debug information - bool verbose = false; - - /// Indicate if gradient should be calculated between each object. - /// This is the normalized vector connecting the closest points on the two objects. - bool compute_gradient = false; -}; - -/** \brief Generic representation of the distance information for a pair of objects */ -// TODO(#267): Enable check - for some reason clang-tidy wants to rename this struct to "i0" -struct DistanceResultsData // NOLINT(readability-identifier-naming) - suppress spurious clang-tidy warning -{ - DistanceResultsData() - { - clear(); - } - - /// The distance between two objects. If two objects are in collision, distance <= 0. - double distance; - - EIGEN_MAKE_ALIGNED_OPERATOR_NEW - - /// The nearest points - Eigen::Vector3d nearest_points[2]; - - /// The object link names - std::string link_names[2]; - - /// The object body type - BodyType body_types[2]; - - /** Normalized vector connecting closest points (from link_names[0] to link_names[1]) - - Usually, when checking convex to convex, the normal is connecting closest points. - However, FCL in case of non-convex to non-convex or convex to non-convex returns - the contact normal for one of the two triangles that are in contact. */ - Eigen::Vector3d normal; - - /// Clear structure data - void clear() - { - distance = std::numeric_limits::max(); - nearest_points[0].setZero(); - nearest_points[1].setZero(); - body_types[0] = BodyType::WORLD_OBJECT; - body_types[1] = BodyType::WORLD_OBJECT; - link_names[0] = ""; - link_names[1] = ""; - normal.setZero(); - } - - /// Compare if the distance is less than another - bool operator<(const DistanceResultsData& other) - { - return (distance < other.distance); - } - - /// Compare if the distance is greater than another - bool operator>(const DistanceResultsData& other) - { - return (distance > other.distance); - } -}; - -/** \brief Mapping between the names of the collision objects and the DistanceResultData. */ -using DistanceMap = std::map, std::vector >; - -/** \brief Result of a distance request. */ -struct DistanceResult -{ - /// Indicates if two objects were in collision - bool collision = false; - - /// ResultsData for the two objects with the minimum distance - DistanceResultsData minimum_distance; - - /// A map of distance data for each link in the req.active_components_only - DistanceMap distances; - - /// Clear structure data - void clear() - { - collision = false; - minimum_distance.clear(); - distances.clear(); - } -}; - -/** \brief Representation of a collision checking result */ -struct CollisionResult -{ - EIGEN_MAKE_ALIGNED_OPERATOR_NEW - - /** \brief Clear a previously stored result */ - void clear() - { - collision = false; - distance = std::numeric_limits::max(); - distance_result.clear(); - contact_count = 0; - contacts.clear(); - cost_sources.clear(); - } - - /** \brief Throttled warning printing the first collision pair, if any. All collisions are logged at DEBUG level */ - void print() const; - - /** \brief True if collision was found, false otherwise */ - bool collision = false; - - /** \brief Closest distance between two bodies */ - double distance = std::numeric_limits::max(); - - /** \brief Distance data for each link */ - DistanceResult distance_result; - - /** \brief Number of contacts returned */ - std::size_t contact_count = 0; - - /** \brief A map returning the pairs of body ids in contact, plus their contact details */ - using ContactMap = std::map, std::vector >; - ContactMap contacts; - - /** \brief These are the individual cost sources when costs are computed */ - std::set cost_sources; -}; -} // namespace collision_detection diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.hpp b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.hpp index 49d12da47d..19777a044f 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.hpp +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.hpp @@ -150,6 +150,12 @@ struct CollisionRequest * are included. */ std::string group_name = ""; + /** \brief If true, use padded collision environment */ + bool pad_environment_collisions = true; + + /** \brief If true, do self collision check with padded robot links */ + bool pad_self_collisions = false; + /** \brief If true, compute proximity distance */ bool distance = false; diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h deleted file mode 100644 index 37d7c9787c..0000000000 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h +++ /dev/null @@ -1,1003 +0,0 @@ -/********************************************************************* - * Software License Agreement (BSD License) - * - * Copyright (c) 2011, Willow Garage, Inc. - * 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 Willow Garage 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. - *********************************************************************/ - -/* Author: Ioan Sucan, Acorn Pooley */ - -#pragma once - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include - -/** \brief This namespace includes the central class for representing planning contexts */ -namespace planning_scene -{ -MOVEIT_CLASS_FORWARD(PlanningScene); // Defines PlanningScenePtr, ConstPtr, WeakPtr... etc - -/** \brief This is the function signature for additional feasibility checks to be imposed on states (in addition to - respecting constraints and collision avoidance). - The first argument is the state to check the feasibility for, the second one is whether the check should be verbose - or not. */ -typedef std::function StateFeasibilityFn; - -/** \brief This is the function signature for additional feasibility checks to be imposed on motions segments between - states (in addition to respecting constraints and collision avoidance). - The order of the arguments matters: the notion of feasibility is to be checked for motion segments that start at the - first state and end at the second state. The third argument indicates - whether the check should be verbose or not. */ -using MotionFeasibilityFn = std::function; - -/** \brief A map from object names (e.g., attached bodies, collision objects) to their colors */ -using ObjectColorMap = std::map; - -/** \brief A map from object names (e.g., attached bodies, collision objects) to their types */ -using ObjectTypeMap = std::map; - -/** \brief This class maintains the representation of the - environment as seen by a planning instance. The environment - geometry, the robot geometry and state are maintained. */ -class MOVEIT_PLANNING_SCENE_EXPORT PlanningScene : public std::enable_shared_from_this -{ -public: - /** - * @brief PlanningScene cannot be copy-constructed - */ - PlanningScene(const PlanningScene&) = delete; - - /** - * @brief PlanningScene cannot be copy-assigned - */ - PlanningScene& operator=(const PlanningScene&) = delete; - - /** \brief construct using an existing RobotModel */ - PlanningScene(const moveit::core::RobotModelConstPtr& robot_model, - const collision_detection::WorldPtr& world = std::make_shared()); - - /** \brief construct using a urdf and srdf. - * A RobotModel for the PlanningScene will be created using the urdf and srdf. */ - PlanningScene(const urdf::ModelInterfaceSharedPtr& urdf_model, const srdf::ModelConstSharedPtr& srdf_model, - const collision_detection::WorldPtr& world = std::make_shared()); - - static const std::string OCTOMAP_NS; - static const std::string DEFAULT_SCENE_NAME; - - ~PlanningScene(); - - /** \brief Get the name of the planning scene. This is empty by default */ - const std::string& getName() const - { - return name_; - } - - /** \brief Set the name of the planning scene */ - void setName(const std::string& name) - { - name_ = name; - } - - /** \brief Return a new child PlanningScene that uses this one as parent. - * - * The child scene has its own copy of the world. It maintains a list (in - * world_diff_) of changes made to the child world. - * - * The robot_model_, robot_state_, scene_transforms_, and acm_ are not copied. - * They are shared with the parent. So if changes to these are made in the parent they will be visible in the child. - * But if any of these is modified (i.e. if the get*NonConst functions are called) in the child then a copy is made - * and subsequent changes to the corresponding member of the parent will no longer be visible in the child. - */ - PlanningScenePtr diff() const; - - /** \brief Return a new child PlanningScene that uses this one as parent and - * has the diffs specified by \e msg applied. */ - PlanningScenePtr diff(const moveit_msgs::msg::PlanningScene& msg) const; - - /** \brief Get the parent scene (with respect to which the diffs are maintained). This may be empty */ - const PlanningSceneConstPtr& getParent() const - { - return parent_; - } - - /** \brief Get the kinematic model for which the planning scene is maintained */ - const moveit::core::RobotModelConstPtr& getRobotModel() const - { - // the kinematic model does not change - return robot_model_; - } - - /** \brief Get the state at which the robot is assumed to be. */ - const moveit::core::RobotState& getCurrentState() const - { - // if we have an updated state, return it; otherwise, return the parent one - return robot_state_.has_value() ? robot_state_.value() : parent_->getCurrentState(); - } - /** \brief Get the state at which the robot is assumed to be. */ - moveit::core::RobotState& getCurrentStateNonConst(); - - /** \brief Get a copy of the current state with components overwritten by the state message \e update */ - moveit::core::RobotStatePtr getCurrentStateUpdated(const moveit_msgs::msg::RobotState& update) const; - - /** - * \name Reasoning about frames - */ - /**@{*/ - - /** \brief Get the frame in which planning is performed */ - const std::string& getPlanningFrame() const - { - // if we have an updated set of transforms, return it; otherwise, return the parent one - return scene_transforms_.has_value() ? scene_transforms_.value()->getTargetFrame() : parent_->getPlanningFrame(); - } - - /** \brief Get the set of fixed transforms from known frames to the planning frame */ - const moveit::core::Transforms& getTransforms() const - { - if (scene_transforms_.has_value() || !parent_) - { - return *scene_transforms_.value(); - } - - // if this planning scene is a child of another, and doesn't have its own custom transforms - return parent_->getTransforms(); - } - - /** \brief Get the set of fixed transforms from known frames to the planning frame. This variant is non-const and also - * updates the current state */ - const moveit::core::Transforms& getTransforms(); - - /** \brief Get the set of fixed transforms from known frames to the planning frame */ - moveit::core::Transforms& getTransformsNonConst(); - - /** \brief Get the transform corresponding to the frame \e id. This will be known if \e id is a link name, an attached - body id or a collision object. - Return identity when no transform is available. Use knowsFrameTransform() to test if this function will be - successful or not. */ - const Eigen::Isometry3d& getFrameTransform(const std::string& id) const; - - /** \brief Get the transform corresponding to the frame \e id. This will be known if \e id is a link name, an attached - body id or a collision object. - Return identity when no transform is available. Use knowsFrameTransform() to test if this function will be - successful or not. - Because this function is non-const, the current state transforms are also updated, if needed. */ - const Eigen::Isometry3d& getFrameTransform(const std::string& id); - - /** \brief Get the transform corresponding to the frame \e id. This will be known if \e id is a link name, an attached - body id or a collision object. - Return identity when no transform is available. Use knowsFrameTransform() to test if this function will be - successful or not. This function also - updates the link transforms of \e state. */ - const Eigen::Isometry3d& getFrameTransform(moveit::core::RobotState& state, const std::string& id) const - { - state.updateLinkTransforms(); - return getFrameTransform(static_cast(state), id); - } - - /** \brief Get the transform corresponding to the frame \e id. This will be known if \e id is a link name, an attached - body id or a collision object. - Return identity when no transform is available. Use knowsFrameTransform() to test if this function will be - successful or not. */ - const Eigen::Isometry3d& getFrameTransform(const moveit::core::RobotState& state, const std::string& id) const; - - /** \brief Check if a transform to the frame \e id is known. This will be known if \e id is a link name, an attached - * body id or a collision object */ - bool knowsFrameTransform(const std::string& id) const; - - /** \brief Check if a transform to the frame \e id is known. This will be known if \e id is a link name, an attached - * body id or a collision object */ - bool knowsFrameTransform(const moveit::core::RobotState& state, const std::string& id) const; - - /**@}*/ - - /** - * \name Reasoning about the geometry of the planning scene - */ - /**@{*/ - - const std::string getCollisionDetectorName() const - { - // If no collision detector is allocated, return an empty string - return collision_detector_ ? (collision_detector_->alloc_->getName()) : ""; - } - - /** \brief Get the representation of the world */ - const collision_detection::WorldConstPtr& getWorld() const - { - // we always have a world representation - return world_const_; - } - - /** \brief Get the representation of the world */ - const collision_detection::WorldPtr& getWorldNonConst() - { - // we always have a world representation - return world_; - } - - /** \brief Get the active collision environment */ - const collision_detection::CollisionEnvConstPtr& getCollisionEnv() const - { - return collision_detector_->getCollisionEnv(); - } - - /** \brief Get the active collision detector for the robot */ - const collision_detection::CollisionEnvConstPtr& getCollisionEnvUnpadded() const - { - return collision_detector_->getCollisionEnvUnpadded(); - } - - /** \brief Get a specific collision detector for the world. If not found return active CollisionWorld. */ - const collision_detection::CollisionEnvConstPtr& getCollisionEnv(const std::string& collision_detector_name) const; - - /** \brief Get a specific collision detector for the unpadded robot. If no found return active unpadded - * CollisionRobot. */ - const collision_detection::CollisionEnvConstPtr& - getCollisionEnvUnpadded(const std::string& collision_detector_name) const; - - /** \brief Get the representation of the collision robot - * This can be used to set padding and link scale on the active collision_robot. */ - const collision_detection::CollisionEnvPtr& getCollisionEnvNonConst(); - - /** \brief Get the allowed collision matrix */ - const collision_detection::AllowedCollisionMatrix& getAllowedCollisionMatrix() const - { - return acm_.has_value() ? acm_.value() : parent_->getAllowedCollisionMatrix(); - } - - /** \brief Get the allowed collision matrix */ - collision_detection::AllowedCollisionMatrix& getAllowedCollisionMatrixNonConst(); - - /** \brief Set the allowed collision matrix */ - void setAllowedCollisionMatrix(const collision_detection::AllowedCollisionMatrix& acm); - - /**@}*/ - - /** - * \name Collision checking with respect to this planning scene - */ - /**@{*/ - - /** \brief Check if the current state is in collision (with the environment or self collision). - If a group name is specified, collision checking is done for that group only (plus descendent links). - Since the function is non-const, the current state transforms are updated before the collision check. */ - bool isStateColliding(const std::string& group = "", bool verbose = false); - - /** \brief Check if the current state is in collision (with the environment or self collision). If a group name is - specified, - collision checking is done for that group only (plus descendent links). It is expected the current state - transforms are up to date. */ - bool isStateColliding(const std::string& group = "", bool verbose = false) const - { - return isStateColliding(getCurrentState(), group, verbose); - } - - /** \brief Check if a given state is in collision (with the environment or self collision) If a group name is - specified, - collision checking is done for that group only (plus descendent links). The link transforms for \e state are - updated before the collision check. */ - bool isStateColliding(moveit::core::RobotState& state, const std::string& group = "", bool verbose = false) const - { - state.updateCollisionBodyTransforms(); - return isStateColliding(static_cast(state), group, verbose); - } - - /** \brief Check if a given state is in collision (with the environment or self collision) - If a group name is specified, collision checking is done for that group only (plus descendent links). It is - expected that the link transforms of \e state are up to date. */ - bool isStateColliding(const moveit::core::RobotState& state, const std::string& group = "", - bool verbose = false) const; - - /** \brief Check if a given state is in collision (with the environment or self collision) - If a group name is specified, collision checking is done for that group only (plus descendent links). */ - bool isStateColliding(const moveit_msgs::msg::RobotState& state, const std::string& group = "", - bool verbose = false) const; - - /** \brief Check whether the current state is in collision, and if needed, updates the collision transforms of the - * current state before the computation. */ - void checkCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res); - - /** \brief Check whether the current state is in collision. The current state is expected to be updated. */ - void checkCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res) const; - - /** \brief Check whether a specified state (\e robot_state) is in collision. This variant of the function takes - a non-const \e robot_state and calls updateCollisionBodyTransforms() on it. */ - void checkCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - moveit::core::RobotState& robot_state) const; - - /** \brief Check whether a specified state (\e robot_state) is in collision. The collision transforms of \e - * robot_state are - * expected to be up to date. */ - void checkCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - const moveit::core::RobotState& robot_state) const; - - /** \brief Check whether a specified state (\e robot_state) is in collision, with respect to a given - allowed collision matrix (\e acm). This variant of the function takes - a non-const \e robot_state and updates its link transforms if needed. */ - void checkCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - moveit::core::RobotState& robot_state, - const collision_detection::AllowedCollisionMatrix& acm) const; - - /** \brief Check whether a specified state (\e robot_state) is in collision, with respect to a given - allowed collision matrix (\e acm). */ - void checkCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - const moveit::core::RobotState& robot_state, - const collision_detection::AllowedCollisionMatrix& acm) const; - - /** \brief Check whether the current state is in collision, - but use a collision_detection::CollisionRobot instance that has no padding. - Since the function is non-const, the current state transforms are also updated if needed. */ - [[deprecated("Use new CollisionRequest flags to enable/ disable padding instead.")]] void - checkCollisionUnpadded(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res); - - /** \brief Check whether the current state is in collision, - but use a collision_detection::CollisionRobot instance that has no padding. */ - [[deprecated("Use new CollisionRequest flags to enable/ disable padding instead.")]] void - checkCollisionUnpadded(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res) const; - - /** \brief Check whether a specified state (\e robot_state) is in collision, - but use a collision_detection::CollisionRobot instance that has no padding. */ - [[deprecated("Use new CollisionRequest flags to enable/ disable padding instead.")]] void - checkCollisionUnpadded(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - const moveit::core::RobotState& robot_state) const; - - /** \brief Check whether a specified state (\e robot_state) is in collision, - but use a collision_detection::CollisionRobot instance that has no padding. - Update the link transforms of \e robot_state if needed. */ - [[deprecated("Use new CollisionRequest flags to enable/ disable padding instead.")]] void - checkCollisionUnpadded(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - moveit::core::RobotState& robot_state) const; - - /** \brief Check whether a specified state (\e robot_state) is in collision, with respect to a given - allowed collision matrix (\e acm), but use a collision_detection::CollisionRobot instance that has no padding. - This variant of the function takes a non-const \e robot_state and calls updates the link transforms if needed. */ - [[deprecated("Use new CollisionRequest flags to enable/ disable padding instead.")]] void - checkCollisionUnpadded(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - moveit::core::RobotState& robot_state, - const collision_detection::AllowedCollisionMatrix& acm) const; - - /** \brief Check whether a specified state (\e robot_state) is in collision, with respect to a given - allowed collision matrix (\e acm), but use a collision_detection::CollisionRobot instance that has no padding. */ - [[deprecated("Use new CollisionRequest flags to enable/ disable padding instead.")]] void - checkCollisionUnpadded(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - const moveit::core::RobotState& robot_state, - const collision_detection::AllowedCollisionMatrix& acm) const; - - /** \brief Check whether the current state is in self collision */ - void checkSelfCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res); - - /** \brief Check whether the current state is in self collision */ - void checkSelfCollision(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res) const; - - /** \brief Check whether a specified state (\e robot_state) is in self collision */ - void checkSelfCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - moveit::core::RobotState& robot_state) const; - - /** \brief Check whether a specified state (\e robot_state) is in self collision */ - void checkSelfCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - const moveit::core::RobotState& robot_state) const; - - /** \brief Check whether a specified state (\e robot_state) is in self collision, with respect to a given - allowed collision matrix (\e acm). The link transforms of \e robot_state are updated if needed. */ - void checkSelfCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - moveit::core::RobotState& robot_state, - const collision_detection::AllowedCollisionMatrix& acm) const; - - /** \brief Check whether a specified state (\e robot_state) is in self collision, with respect to a given - allowed collision matrix (\e acm) */ - void checkSelfCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - const moveit::core::RobotState& robot_state, - const collision_detection::AllowedCollisionMatrix& acm) const; - - /** \brief Get the names of the links that are involved in collisions for the current state */ - void getCollidingLinks(std::vector& links); - - /** \brief Get the names of the links that are involved in collisions for the current state */ - void getCollidingLinks(std::vector& links) const - { - getCollidingLinks(links, getCurrentState(), getAllowedCollisionMatrix()); - } - - /** \brief Get the names of the links that are involved in collisions for the state \e robot_state. - Update the link transforms for \e robot_state if needed. */ - void getCollidingLinks(std::vector& links, moveit::core::RobotState& robot_state) const - { - robot_state.updateCollisionBodyTransforms(); - getCollidingLinks(links, static_cast(robot_state), getAllowedCollisionMatrix()); - } - - /** \brief Get the names of the links that are involved in collisions for the state \e robot_state */ - void getCollidingLinks(std::vector& links, const moveit::core::RobotState& robot_state) const - { - getCollidingLinks(links, robot_state, getAllowedCollisionMatrix()); - } - - /** \brief Get the names of the links that are involved in collisions for the state \e robot_state given the - allowed collision matrix (\e acm) */ - void getCollidingLinks(std::vector& links, moveit::core::RobotState& robot_state, - const collision_detection::AllowedCollisionMatrix& acm) const - { - robot_state.updateCollisionBodyTransforms(); - getCollidingLinks(links, static_cast(robot_state), acm); - } - - /** \brief Get the names of the links that are involved in collisions for the state \e robot_state given the - allowed collision matrix (\e acm) */ - void getCollidingLinks(std::vector& links, const moveit::core::RobotState& robot_state, - const collision_detection::AllowedCollisionMatrix& acm) const; - - /** \brief Get the names of the links that are involved in collisions for the current state. - Update the link transforms for the current state if needed. */ - void getCollidingPairs(collision_detection::CollisionResult::ContactMap& contacts); - - /** \brief Get the names of the links that are involved in collisions for the current state */ - void getCollidingPairs(collision_detection::CollisionResult::ContactMap& contacts) const - { - getCollidingPairs(contacts, getCurrentState(), getAllowedCollisionMatrix()); - } - - /** \brief Get the names of the links that are involved in collisions for the state \e robot_state. - * Can be restricted to links part of or updated by \e group_name (plus descendent links) */ - void getCollidingPairs(collision_detection::CollisionResult::ContactMap& contacts, - const moveit::core::RobotState& robot_state, const std::string& group_name = "") const - { - getCollidingPairs(contacts, robot_state, getAllowedCollisionMatrix(), group_name); - } - - /** \brief Get the names of the links that are involved in collisions for the state \e robot_state. - Update the link transforms for \e robot_state if needed. - Can be restricted to links part of or updated by \e group_name (plus descendent links) */ - void getCollidingPairs(collision_detection::CollisionResult::ContactMap& contacts, - moveit::core::RobotState& robot_state, const std::string& group_name = "") const - { - robot_state.updateCollisionBodyTransforms(); - getCollidingPairs(contacts, static_cast(robot_state), getAllowedCollisionMatrix(), - group_name); - } - - /** \brief Get the names of the links that are involved in collisions for the state \e robot_state given the - allowed collision matrix (\e acm). Update the link transforms for \e robot_state if needed. - Can be restricted to links part of or updated by \e group_name (plus descendent links) */ - void getCollidingPairs(collision_detection::CollisionResult::ContactMap& contacts, - moveit::core::RobotState& robot_state, const collision_detection::AllowedCollisionMatrix& acm, - const std::string& group_name = "") const - { - robot_state.updateCollisionBodyTransforms(); - getCollidingPairs(contacts, static_cast(robot_state), acm, group_name); - } - - /** \brief Get the names of the links that are involved in collisions for the state \e robot_state given the - allowed collision matrix (\e acm). Can be restricted to links part of or updated by \e group_name (plus descendent links) */ - void getCollidingPairs(collision_detection::CollisionResult::ContactMap& contacts, - const moveit::core::RobotState& robot_state, - const collision_detection::AllowedCollisionMatrix& acm, - const std::string& group_name = "") const; - - /**@}*/ - - /** - * \name Distance computation - */ - /**@{*/ - - /** \brief The distance between the robot model at state \e robot_state to the nearest collision (ignoring - * self-collisions) - */ - double distanceToCollision(moveit::core::RobotState& robot_state) const - { - robot_state.updateCollisionBodyTransforms(); - return distanceToCollision(static_cast(robot_state)); - } - - /** \brief The distance between the robot model at state \e robot_state to the nearest collision (ignoring - * self-collisions) - */ - double distanceToCollision(const moveit::core::RobotState& robot_state) const - { - return getCollisionEnv()->distanceRobot(robot_state, getAllowedCollisionMatrix()); - } - - /** \brief The distance between the robot model at state \e robot_state to the nearest collision (ignoring - * self-collisions), if the robot has no padding */ - double distanceToCollisionUnpadded(moveit::core::RobotState& robot_state) const - { - robot_state.updateCollisionBodyTransforms(); - return distanceToCollisionUnpadded(static_cast(robot_state)); - } - - /** \brief The distance between the robot model at state \e robot_state to the nearest collision (ignoring - * self-collisions), if the robot has no padding */ - double distanceToCollisionUnpadded(const moveit::core::RobotState& robot_state) const - { - return getCollisionEnvUnpadded()->distanceRobot(robot_state, getAllowedCollisionMatrix()); - } - - /** \brief The distance between the robot model at state \e robot_state to the nearest collision, ignoring - * self-collisions - * and elements that are allowed to collide. */ - double distanceToCollision(moveit::core::RobotState& robot_state, - const collision_detection::AllowedCollisionMatrix& acm) const - { - robot_state.updateCollisionBodyTransforms(); - return distanceToCollision(static_cast(robot_state), acm); - } - - /** \brief The distance between the robot model at state \e robot_state to the nearest collision, ignoring - * self-collisions - * and elements that are allowed to collide. */ - double distanceToCollision(const moveit::core::RobotState& robot_state, - const collision_detection::AllowedCollisionMatrix& acm) const - { - return getCollisionEnv()->distanceRobot(robot_state, acm); - } - - /** \brief The distance between the robot model at state \e robot_state to the nearest collision, ignoring - * self-collisions - * and elements that are allowed to collide, if the robot has no padding. */ - double distanceToCollisionUnpadded(moveit::core::RobotState& robot_state, - const collision_detection::AllowedCollisionMatrix& acm) const - { - robot_state.updateCollisionBodyTransforms(); - return distanceToCollisionUnpadded(static_cast(robot_state), acm); - } - - /** \brief The distance between the robot model at state \e robot_state to the nearest collision, ignoring - * self-collisions - * and elements that always allowed to collide, if the robot has no padding. */ - double distanceToCollisionUnpadded(const moveit::core::RobotState& robot_state, - const collision_detection::AllowedCollisionMatrix& acm) const - { - return getCollisionEnvUnpadded()->distanceRobot(robot_state, acm); - } - - /**@}*/ - - /** \brief Save the geometry of the planning scene to a stream, as plain text */ - void saveGeometryToStream(std::ostream& out) const; - - /** \brief Load the geometry of the planning scene from a stream */ - bool loadGeometryFromStream(std::istream& in); - - /** \brief Load the geometry of the planning scene from a stream at a certain location using offset*/ - bool loadGeometryFromStream(std::istream& in, const Eigen::Isometry3d& offset); - - /** \brief Fill the message \e scene with the differences between this instance of PlanningScene with respect to the - parent. - If there is no parent, everything is considered to be a diff and the function behaves like getPlanningSceneMsg() - */ - void getPlanningSceneDiffMsg(moveit_msgs::msg::PlanningScene& scene) const; - - /** \brief Construct a message (\e scene) with all the necessary data so that the scene can be later reconstructed to - be - exactly the same using setPlanningSceneMsg() */ - void getPlanningSceneMsg(moveit_msgs::msg::PlanningScene& scene) const; - - /** \brief Construct a message (\e scene) with the data requested in \e comp. If all options in \e comp are filled, - this will be a complete planning scene message */ - void getPlanningSceneMsg(moveit_msgs::msg::PlanningScene& scene, - const moveit_msgs::msg::PlanningSceneComponents& comp) const; - - /** \brief Construct a message (\e collision_object) with the collision object data from the planning_scene for the - * requested object*/ - bool getCollisionObjectMsg(moveit_msgs::msg::CollisionObject& collision_obj, const std::string& ns) const; - - /** \brief Construct a vector of messages (\e collision_objects) with the collision object data for all objects in - * planning_scene */ - void getCollisionObjectMsgs(std::vector& collision_objs) const; - - /** \brief Construct a message (\e attached_collision_object) with the attached collision object data from the - * planning_scene for the requested object*/ - bool getAttachedCollisionObjectMsg(moveit_msgs::msg::AttachedCollisionObject& attached_collision_obj, - const std::string& ns) const; - - /** \brief Construct a vector of messages (\e attached_collision_objects) with the attached collision object data for - * all objects in planning_scene */ - void - getAttachedCollisionObjectMsgs(std::vector& attached_collision_objs) const; - - /** \brief Construct a message (\e octomap) with the octomap data from the planning_scene */ - bool getOctomapMsg(octomap_msgs::msg::OctomapWithPose& octomap) const; - - /** \brief Construct a vector of messages (\e object_colors) with the colors of the objects from the planning_scene */ - void getObjectColorMsgs(std::vector& object_colors) const; - - /** \brief Apply changes to this planning scene as diffs, even if the message itself is not marked as being a diff - (is_diff - member). A parent is not required to exist. However, the existing data in the planning instance is not cleared. - Data from - the message is only appended (and in cases such as e.g., the robot state, is overwritten). */ - bool setPlanningSceneDiffMsg(const moveit_msgs::msg::PlanningScene& scene); - - /** \brief Set this instance of a planning scene to be the same as the one serialized in the \e scene message, even if - * the message itself is marked as being a diff (is_diff member) */ - bool setPlanningSceneMsg(const moveit_msgs::msg::PlanningScene& scene); - - /** \brief Call setPlanningSceneMsg() or setPlanningSceneDiffMsg() depending on how the is_diff member of the message - * is set */ - bool usePlanningSceneMsg(const moveit_msgs::msg::PlanningScene& scene); - - /** \brief Takes the object message and returns the object pose, shapes and shape poses. - * If the object pose is empty (identity) but the shape pose is set, this uses the shape - * pose as the object pose. The shape pose becomes the identity instead. - */ - bool shapesAndPosesFromCollisionObjectMessage(const moveit_msgs::msg::CollisionObject& object, - Eigen::Isometry3d& object_pose_in_header_frame, - std::vector& shapes, - EigenSTL::vector_Isometry3d& shape_poses); - - bool processCollisionObjectMsg(const moveit_msgs::msg::CollisionObject& object); - bool processAttachedCollisionObjectMsg(const moveit_msgs::msg::AttachedCollisionObject& object); - - bool processPlanningSceneWorldMsg(const moveit_msgs::msg::PlanningSceneWorld& world); - - void processOctomapMsg(const octomap_msgs::msg::OctomapWithPose& map); - void processOctomapMsg(const octomap_msgs::msg::Octomap& map); - void processOctomapPtr(const std::shared_ptr& octree, const Eigen::Isometry3d& t); - - /** - * \brief Clear all collision objects in planning scene - */ - void removeAllCollisionObjects(); - - /** \brief Set the current robot state to be \e state. If not - all joint values are specified, the previously maintained - joint values are kept. */ - void setCurrentState(const moveit_msgs::msg::RobotState& state); - - /** \brief Set the current robot state */ - void setCurrentState(const moveit::core::RobotState& state); - - /** \brief Set the callback to be triggered when changes are made to the current scene state */ - void setAttachedBodyUpdateCallback(const moveit::core::AttachedBodyCallback& callback); - - /** \brief Set the callback to be triggered when changes are made to the current scene world */ - void setCollisionObjectUpdateCallback(const collision_detection::World::ObserverCallbackFn& callback); - - bool hasObjectColor(const std::string& id) const; - - /** - * \brief Gets the current color of an object. - * \param id The string id of the target object. - * \return The current object color. - */ - const std_msgs::msg::ColorRGBA& getObjectColor(const std::string& id) const; - - /** - * \brief Tries to get the original color of an object, if one has been set before. - * \param id The string id of the target object. - * \return The original object color, if available, otherwise std::nullopt. - */ - std::optional getOriginalObjectColor(const std::string& id) const; - - void setObjectColor(const std::string& id, const std_msgs::msg::ColorRGBA& color); - void removeObjectColor(const std::string& id); - void getKnownObjectColors(ObjectColorMap& kc) const; - - bool hasObjectType(const std::string& id) const; - - const object_recognition_msgs::msg::ObjectType& getObjectType(const std::string& id) const; - void setObjectType(const std::string& id, const object_recognition_msgs::msg::ObjectType& type); - void removeObjectType(const std::string& id); - void getKnownObjectTypes(ObjectTypeMap& kc) const; - - /** \brief Clear the diffs accumulated for this planning scene, with respect to: - * the parent PlanningScene (if it exists) - * the parent CollisionDetector (if it exists) - * This function is a no-op if there is no parent planning scene. */ - void clearDiffs(); - - /** \brief If there is a parent specified for this scene, then the diffs with respect to that parent are applied to a - specified planning scene, whatever - that scene may be. If there is no parent specified, this function is a no-op. */ - void pushDiffs(const PlanningScenePtr& scene); - - /** \brief Make sure that all the data maintained in this - scene is local. All unmodified data is copied from the - parent and the pointer to the parent is discarded. */ - void decoupleParent(); - - /** \brief Specify a predicate that decides whether states are considered valid or invalid for reasons beyond ones - covered by collision checking and constraint evaluation. - This is useful for setting up problem specific constraints (e.g., stability) */ - void setStateFeasibilityPredicate(const StateFeasibilityFn& fn) - { - state_feasibility_ = fn; - } - - /** \brief Get the predicate that decides whether states are considered valid or invalid for reasons beyond ones - * covered by collision checking and constraint evaluation. */ - const StateFeasibilityFn& getStateFeasibilityPredicate() const - { - return state_feasibility_; - } - - /** \brief Specify a predicate that decides whether motion segments are considered valid or invalid for reasons beyond - * ones covered by collision checking and constraint evaluation. */ - void setMotionFeasibilityPredicate(const MotionFeasibilityFn& fn) - { - motion_feasibility_ = fn; - } - - /** \brief Get the predicate that decides whether motion segments are considered valid or invalid for reasons beyond - * ones covered by collision checking and constraint evaluation. */ - const MotionFeasibilityFn& getMotionFeasibilityPredicate() const - { - return motion_feasibility_; - } - - /** \brief Check if a given state is feasible, in accordance to the feasibility predicate specified by - * setStateFeasibilityPredicate(). Returns true if no feasibility predicate was specified. */ - bool isStateFeasible(const moveit_msgs::msg::RobotState& state, bool verbose = false) const; - - /** \brief Check if a given state is feasible, in accordance to the feasibility predicate specified by - * setStateFeasibilityPredicate(). Returns true if no feasibility predicate was specified. */ - bool isStateFeasible(const moveit::core::RobotState& state, bool verbose = false) const; - - /** \brief Check if a given state satisfies a set of constraints */ - bool isStateConstrained(const moveit_msgs::msg::RobotState& state, const moveit_msgs::msg::Constraints& constr, - bool verbose = false) const; - - /** \brief Check if a given state satisfies a set of constraints */ - bool isStateConstrained(const moveit::core::RobotState& state, const moveit_msgs::msg::Constraints& constr, - bool verbose = false) const; - - /** \brief Check if a given state satisfies a set of constraints */ - bool isStateConstrained(const moveit_msgs::msg::RobotState& state, - const kinematic_constraints::KinematicConstraintSet& constr, bool verbose = false) const; - - /** \brief Check if a given state satisfies a set of constraints */ - bool isStateConstrained(const moveit::core::RobotState& state, - const kinematic_constraints::KinematicConstraintSet& constr, bool verbose = false) const; - - /** \brief Check if a given state is valid. This means checking for collisions and feasibility. Includes descendent - * links of \e group. */ - bool isStateValid(const moveit_msgs::msg::RobotState& state, const std::string& group = "", - bool verbose = false) const; - - /** \brief Check if a given state is valid. This means checking for collisions and feasibility. Includes descendent - * links of \e group. */ - bool isStateValid(const moveit::core::RobotState& state, const std::string& group = "", bool verbose = false) const; - - /** \brief Check if a given state is valid. This means checking for collisions, feasibility and whether the user - * specified validity conditions hold as well. Includes descendent links of \e group. */ - bool isStateValid(const moveit_msgs::msg::RobotState& state, const moveit_msgs::msg::Constraints& constr, - const std::string& group = "", bool verbose = false) const; - - /** \brief Check if a given state is valid. This means checking for collisions, feasibility and whether the user - * specified validity conditions hold as well. Includes descendent links of \e group. */ - bool isStateValid(const moveit::core::RobotState& state, const moveit_msgs::msg::Constraints& constr, - const std::string& group = "", bool verbose = false) const; - - /** \brief Check if a given state is valid. This means checking for collisions, feasibility and whether the user - * specified validity conditions hold as well. Includes descendent links of \e group. */ - bool isStateValid(const moveit::core::RobotState& state, const kinematic_constraints::KinematicConstraintSet& constr, - const std::string& group = "", bool verbose = false) const; - - /** \brief Check if a given path is valid. Each state is checked for validity (collision avoidance and feasibility). - * Includes descendent links of \e group. */ - bool isPathValid(const moveit_msgs::msg::RobotState& start_state, const moveit_msgs::msg::RobotTrajectory& trajectory, - const std::string& group = "", bool verbose = false, - std::vector* invalid_index = nullptr) const; - - /** \brief Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and - * constraint satisfaction). It is also checked that the goal constraints are satisfied by the last state on the - * passed in trajectory. Includes descendent links of \e group. */ - bool isPathValid(const moveit_msgs::msg::RobotState& start_state, const moveit_msgs::msg::RobotTrajectory& trajectory, - const moveit_msgs::msg::Constraints& path_constraints, const std::string& group = "", - bool verbose = false, std::vector* invalid_index = nullptr) const; - - /** \brief Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and - * constraint satisfaction). It is also checked that the goal constraints are satisfied by the last state on the - * passed in trajectory. Includes descendent links of \e group. */ - bool isPathValid(const moveit_msgs::msg::RobotState& start_state, const moveit_msgs::msg::RobotTrajectory& trajectory, - const moveit_msgs::msg::Constraints& path_constraints, - const moveit_msgs::msg::Constraints& goal_constraints, const std::string& group = "", - bool verbose = false, std::vector* invalid_index = nullptr) const; - - /** \brief Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and - * constraint satisfaction). It is also checked that the goal constraints are satisfied by the last state on the - * passed in trajectory. Includes descendent links of \e group. */ - bool isPathValid(const moveit_msgs::msg::RobotState& start_state, const moveit_msgs::msg::RobotTrajectory& trajectory, - const moveit_msgs::msg::Constraints& path_constraints, - const std::vector& goal_constraints, const std::string& group = "", - bool verbose = false, std::vector* invalid_index = nullptr) const; - - /** \brief Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and - * constraint satisfaction). It is also checked that the goal constraints are satisfied by the last state on the - * passed in trajectory. Includes descendent links of \e group. */ - bool isPathValid(const robot_trajectory::RobotTrajectory& trajectory, - const moveit_msgs::msg::Constraints& path_constraints, - const std::vector& goal_constraints, const std::string& group = "", - bool verbose = false, std::vector* invalid_index = nullptr) const; - - /** \brief Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and - * constraint satisfaction). It is also checked that the goal constraints are satisfied by the last state on the - * passed in trajectory. Includes descendent links of \e group. */ - bool isPathValid(const robot_trajectory::RobotTrajectory& trajectory, - const moveit_msgs::msg::Constraints& path_constraints, - const moveit_msgs::msg::Constraints& goal_constraints, const std::string& group = "", - bool verbose = false, std::vector* invalid_index = nullptr) const; - - /** \brief Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and - * constraint satisfaction). Includes descendent links of \e group. */ - bool isPathValid(const robot_trajectory::RobotTrajectory& trajectory, - const moveit_msgs::msg::Constraints& path_constraints, const std::string& group = "", - bool verbose = false, std::vector* invalid_index = nullptr) const; - - /** \brief Check if a given path is valid. Each state is checked for validity (collision avoidance and feasibility). - * Includes descendent links of \e group. */ - bool isPathValid(const robot_trajectory::RobotTrajectory& trajectory, const std::string& group = "", - bool verbose = false, std::vector* invalid_index = nullptr) const; - - /** \brief Get the top \e max_costs cost sources for a specified trajectory. The resulting costs are stored in \e - * costs */ - void getCostSources(const robot_trajectory::RobotTrajectory& trajectory, std::size_t max_costs, - std::set& costs, double overlap_fraction = 0.9) const; - - /** \brief Get the top \e max_costs cost sources for a specified trajectory, but only for group \e group_name (plus - * descendent links). The resulting costs are stored in \e costs */ - void getCostSources(const robot_trajectory::RobotTrajectory& trajectory, std::size_t max_costs, - const std::string& group_name, std::set& costs, - double overlap_fraction = 0.9) const; - - /** \brief Get the top \e max_costs cost sources for a specified state. The resulting costs are stored in \e costs */ - void getCostSources(const moveit::core::RobotState& state, std::size_t max_costs, - std::set& costs) const; - - /** \brief Get the top \e max_costs cost sources for a specified state, but only for group \e group_name (plus - * descendent links). The resulting costs are stored in \e costs */ - void getCostSources(const moveit::core::RobotState& state, std::size_t max_costs, const std::string& group_name, - std::set& costs) const; - - /** \brief Outputs debug information about the planning scene contents */ - void printKnownObjects(std::ostream& out = std::cout) const; - - /** \brief Clone a planning scene. Even if the scene \e scene depends on a parent, the cloned scene will not. */ - static PlanningScenePtr clone(const PlanningSceneConstPtr& scene); - - /** \brief Allocate a new collision detector and replace the previous one if there was any. - * - * The collision detector type is specified with (a shared pointer to) an - * allocator which is a subclass of CollisionDetectorAllocator. This - * identifies a combination of CollisionWorld/CollisionRobot which can be - * used together. - * - * A new PlanningScene uses an FCL collision detector by default. - * - * example: to add FCL collision detection (normally not necessary) call - * planning_scene->allocateCollisionDetector(collision_detection::CollisionDetectorAllocatorFCL::create()); - * - * */ - void allocateCollisionDetector(const collision_detection::CollisionDetectorAllocatorPtr& allocator) - { - allocateCollisionDetector(allocator, nullptr /* no parent_detector */); - } - -private: - /* Private constructor used by the diff() methods. */ - PlanningScene(const PlanningSceneConstPtr& parent); - - /* Initialize the scene. This should only be called by the constructors. - * Requires a valid robot_model_ */ - void initialize(); - - /* Helper functions for processing collision objects */ - bool processCollisionObjectAdd(const moveit_msgs::msg::CollisionObject& object); - bool processCollisionObjectRemove(const moveit_msgs::msg::CollisionObject& object); - bool processCollisionObjectMove(const moveit_msgs::msg::CollisionObject& object); - - MOVEIT_STRUCT_FORWARD(CollisionDetector); - - /* Construct a new CollisionDector from allocator, copy-construct environments from parent_detector if not nullptr */ - void allocateCollisionDetector(const collision_detection::CollisionDetectorAllocatorPtr& allocator, - const CollisionDetectorPtr& parent_detector); - - /* \brief A set of compatible collision detectors */ - struct CollisionDetector - { - collision_detection::CollisionDetectorAllocatorPtr alloc_; - collision_detection::CollisionEnvPtr cenv_; // never nullptr - collision_detection::CollisionEnvConstPtr cenv_const_; - - collision_detection::CollisionEnvPtr cenv_unpadded_; - collision_detection::CollisionEnvConstPtr cenv_unpadded_const_; - - const collision_detection::CollisionEnvConstPtr& getCollisionEnv() const - { - return cenv_const_; - } - const collision_detection::CollisionEnvConstPtr& getCollisionEnvUnpadded() const - { - return cenv_unpadded_const_; - } - void copyPadding(const CollisionDetector& src); - }; - friend struct CollisionDetector; - - std::string name_; // may be empty - - PlanningSceneConstPtr parent_; // Null unless this is a diff scene - - moveit::core::RobotModelConstPtr robot_model_; // Never null (may point to same model as parent) - - std::optional robot_state_; // if there is no value use parent's - - // Called when changes are made to attached bodies - moveit::core::AttachedBodyCallback current_state_attached_body_callback_; - - // This variable is not necessarily used by child planning scenes - // This Transforms class is actually a SceneTransforms class - std::optional scene_transforms_; // if there is no value use parent's - - collision_detection::WorldPtr world_; // never nullptr, never shared with parent/child - collision_detection::WorldConstPtr world_const_; // copy of world_ - collision_detection::WorldDiffPtr world_diff_; // nullptr unless this is a diff scene - collision_detection::World::ObserverCallbackFn current_world_object_update_callback_; - collision_detection::World::ObserverHandle current_world_object_update_observer_handle_; - - CollisionDetectorPtr collision_detector_; // Never nullptr. - - std::optional acm_; // if there is no value use parent's - - StateFeasibilityFn state_feasibility_; - MotionFeasibilityFn motion_feasibility_; - - // Maps of current and original object colors (to manage attaching/detaching objects) - std::unique_ptr object_colors_; - std::unique_ptr original_object_colors_; - - // a map of object types - std::optional object_types_; -}; -} // namespace planning_scene diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.hpp b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.hpp index 7141900012..a141b9f7e5 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.hpp +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.hpp @@ -347,19 +347,12 @@ class MOVEIT_PLANNING_SCENE_EXPORT PlanningScene : public std::enable_shared_fro void checkCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res); /** \brief Check whether the current state is in collision. The current state is expected to be updated. */ - void checkCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res) const - { - checkCollision(req, res, getCurrentState()); - } + void checkCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res) const; /** \brief Check whether a specified state (\e robot_state) is in collision. This variant of the function takes a non-const \e robot_state and calls updateCollisionBodyTransforms() on it. */ void checkCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - moveit::core::RobotState& robot_state) const - { - robot_state.updateCollisionBodyTransforms(); - checkCollision(req, res, static_cast(robot_state)); - } + moveit::core::RobotState& robot_state) const; /** \brief Check whether a specified state (\e robot_state) is in collision. The collision transforms of \e * robot_state are @@ -372,11 +365,7 @@ class MOVEIT_PLANNING_SCENE_EXPORT PlanningScene : public std::enable_shared_fro a non-const \e robot_state and updates its link transforms if needed. */ void checkCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, moveit::core::RobotState& robot_state, - const collision_detection::AllowedCollisionMatrix& acm) const - { - robot_state.updateCollisionBodyTransforms(); - checkCollision(req, res, static_cast(robot_state), acm); - } + const collision_detection::AllowedCollisionMatrix& acm) const; /** \brief Check whether a specified state (\e robot_state) is in collision, with respect to a given allowed collision matrix (\e acm). */ @@ -387,99 +376,69 @@ class MOVEIT_PLANNING_SCENE_EXPORT PlanningScene : public std::enable_shared_fro /** \brief Check whether the current state is in collision, but use a collision_detection::CollisionRobot instance that has no padding. Since the function is non-const, the current state transforms are also updated if needed. */ - void checkCollisionUnpadded(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res); + [[deprecated("Use new CollisionRequest flags to enable/ disable padding instead.")]] void + checkCollisionUnpadded(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res); /** \brief Check whether the current state is in collision, but use a collision_detection::CollisionRobot instance that has no padding. */ - void checkCollisionUnpadded(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res) const - { - checkCollisionUnpadded(req, res, getCurrentState(), getAllowedCollisionMatrix()); - } + [[deprecated("Use new CollisionRequest flags to enable/ disable padding instead.")]] void + checkCollisionUnpadded(const collision_detection::CollisionRequest& req, + collision_detection::CollisionResult& res) const; /** \brief Check whether a specified state (\e robot_state) is in collision, but use a collision_detection::CollisionRobot instance that has no padding. */ - void checkCollisionUnpadded(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res, - const moveit::core::RobotState& robot_state) const - { - checkCollisionUnpadded(req, res, robot_state, getAllowedCollisionMatrix()); - } + [[deprecated("Use new CollisionRequest flags to enable/ disable padding instead.")]] void + checkCollisionUnpadded(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, + const moveit::core::RobotState& robot_state) const; /** \brief Check whether a specified state (\e robot_state) is in collision, but use a collision_detection::CollisionRobot instance that has no padding. Update the link transforms of \e robot_state if needed. */ - void checkCollisionUnpadded(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res, moveit::core::RobotState& robot_state) const - { - robot_state.updateCollisionBodyTransforms(); - checkCollisionUnpadded(req, res, static_cast(robot_state), - getAllowedCollisionMatrix()); - } + [[deprecated("Use new CollisionRequest flags to enable/ disable padding instead.")]] void + checkCollisionUnpadded(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, + moveit::core::RobotState& robot_state) const; /** \brief Check whether a specified state (\e robot_state) is in collision, with respect to a given allowed collision matrix (\e acm), but use a collision_detection::CollisionRobot instance that has no padding. This variant of the function takes a non-const \e robot_state and calls updates the link transforms if needed. */ - void checkCollisionUnpadded(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res, moveit::core::RobotState& robot_state, - const collision_detection::AllowedCollisionMatrix& acm) const - { - robot_state.updateCollisionBodyTransforms(); - checkCollisionUnpadded(req, res, static_cast(robot_state), acm); - } + [[deprecated("Use new CollisionRequest flags to enable/ disable padding instead.")]] void + checkCollisionUnpadded(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, + moveit::core::RobotState& robot_state, + const collision_detection::AllowedCollisionMatrix& acm) const; /** \brief Check whether a specified state (\e robot_state) is in collision, with respect to a given allowed collision matrix (\e acm), but use a collision_detection::CollisionRobot instance that has no padding. */ - void checkCollisionUnpadded(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res, const moveit::core::RobotState& robot_state, - const collision_detection::AllowedCollisionMatrix& acm) const; + [[deprecated("Use new CollisionRequest flags to enable/ disable padding instead.")]] void + checkCollisionUnpadded(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, + const moveit::core::RobotState& robot_state, + const collision_detection::AllowedCollisionMatrix& acm) const; /** \brief Check whether the current state is in self collision */ void checkSelfCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res); /** \brief Check whether the current state is in self collision */ void checkSelfCollision(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res) const - { - checkSelfCollision(req, res, getCurrentState()); - } + collision_detection::CollisionResult& res) const; /** \brief Check whether a specified state (\e robot_state) is in self collision */ void checkSelfCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - moveit::core::RobotState& robot_state) const - { - robot_state.updateCollisionBodyTransforms(); - checkSelfCollision(req, res, static_cast(robot_state), getAllowedCollisionMatrix()); - } + moveit::core::RobotState& robot_state) const; /** \brief Check whether a specified state (\e robot_state) is in self collision */ void checkSelfCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - const moveit::core::RobotState& robot_state) const - { - // do self-collision checking with the unpadded version of the robot - getCollisionEnvUnpadded()->checkSelfCollision(req, res, robot_state, getAllowedCollisionMatrix()); - } + const moveit::core::RobotState& robot_state) const; /** \brief Check whether a specified state (\e robot_state) is in self collision, with respect to a given allowed collision matrix (\e acm). The link transforms of \e robot_state are updated if needed. */ void checkSelfCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, moveit::core::RobotState& robot_state, - const collision_detection::AllowedCollisionMatrix& acm) const - { - robot_state.updateCollisionBodyTransforms(); - checkSelfCollision(req, res, static_cast(robot_state), acm); - } + const collision_detection::AllowedCollisionMatrix& acm) const; /** \brief Check whether a specified state (\e robot_state) is in self collision, with respect to a given allowed collision matrix (\e acm) */ void checkSelfCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, const moveit::core::RobotState& robot_state, - const collision_detection::AllowedCollisionMatrix& acm) const - { - // do self-collision checking with the unpadded version of the robot - getCollisionEnvUnpadded()->checkSelfCollision(req, res, robot_state, acm); - } + const collision_detection::AllowedCollisionMatrix& acm) const; /** \brief Get the names of the links that are involved in collisions for the current state */ void getCollidingLinks(std::vector& links); From 45640948ef967a81e6b71134b4ada31297932cbd Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Tue, 19 Nov 2024 19:54:24 +0000 Subject: [PATCH 27/53] Adds CMake wrapper around python script --- moveit_common/CMakeLists.txt | 1 + moveit_common/cmake/deprecated_headers.cmake | 37 +++++++++++++++++++ moveit_common/moveit_common-extras.cmake | 1 + .../scripts/create_deprecated_headers.py | 19 +++++----- 4 files changed, 48 insertions(+), 10 deletions(-) create mode 100644 moveit_common/cmake/deprecated_headers.cmake rename {moveit => moveit_common}/scripts/create_deprecated_headers.py (80%) diff --git a/moveit_common/CMakeLists.txt b/moveit_common/CMakeLists.txt index c263c6d363..360c8e76d6 100644 --- a/moveit_common/CMakeLists.txt +++ b/moveit_common/CMakeLists.txt @@ -6,3 +6,4 @@ find_package(ament_cmake REQUIRED) ament_package(CONFIG_EXTRAS "moveit_common-extras.cmake") install(DIRECTORY cmake DESTINATION share/moveit_common) +install(DIRECTORY scripts DESTINATION share/moveit_common) diff --git a/moveit_common/cmake/deprecated_headers.cmake b/moveit_common/cmake/deprecated_headers.cmake new file mode 100644 index 0000000000..a53ff9db6f --- /dev/null +++ b/moveit_common/cmake/deprecated_headers.cmake @@ -0,0 +1,37 @@ +# Copyright 2021 PickNik Inc. +# +# 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 the PickNik Inc. 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 HOLDER 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. + +find_package(PythonInterp REQUIRED) +find_package(Python REQUIRED) + +set(SCRIPT ${CMAKE_CURRENT_LIST_DIR}/../scripts/create_deprecated_headers.py) + +macro(CREATE_DEPRECATED_HEADERS) + add_custom_target(${PROJECT_NAME}_deprecated_headers ALL + COMMAND ${PYTHON_EXECUTABLE} ${SCRIPT} ${CMAKE_INSTALL_PREFIX} + ) +endmacro() \ No newline at end of file diff --git a/moveit_common/moveit_common-extras.cmake b/moveit_common/moveit_common-extras.cmake index 08e01eb31b..e844c0cbc2 100644 --- a/moveit_common/moveit_common-extras.cmake +++ b/moveit_common/moveit_common-extras.cmake @@ -26,3 +26,4 @@ # OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. include("${moveit_common_DIR}/moveit_package.cmake") +include("${moveit_common_DIR}/deprecated_headers.cmake") diff --git a/moveit/scripts/create_deprecated_headers.py b/moveit_common/scripts/create_deprecated_headers.py similarity index 80% rename from moveit/scripts/create_deprecated_headers.py rename to moveit_common/scripts/create_deprecated_headers.py index d18fe8a50b..5029138742 100755 --- a/moveit/scripts/create_deprecated_headers.py +++ b/moveit_common/scripts/create_deprecated_headers.py @@ -32,23 +32,22 @@ import sys from pathlib import Path -# TODO: This doesn't work for chomp and pilz -MOVEIT_HPPS = "**/moveit*/**/*.hpp" +ALL_HPPS = "**/*.hpp" USAGE = "Usage: ./generate_deprecated_headers " DEPRECATION = "{0}.h imports are deprecated. Consider using {0}.hpp" - -def create_c_header(hpp_path: str) -> None: - header_directory = hpp_path.parent +def create_c_header(include_directory: Path, hpp_path: Path) -> None: file = hpp_path.name.replace(".hpp", "") - with open(header_directory / f"{file}.h", "w") as h_file: + hpp_import = f"<{hpp_path.relative_to(include_directory)}>" + with open(str(hpp_path).replace("pp", ""), "w") as h_file: h_file.write(f"#warning {DEPRECATION.format(file)}\n") - h_file.write(f"#include <{file}.hpp>\n") + h_file.write(f"#include {hpp_import}\n") if __name__ == "__main__": if len(sys.argv) != 2: sys.exit(USAGE) - install_directory = sys.argv[1] - for hpp_path in Path(install_directory).rglob(MOVEIT_HPPS): - create_c_header(hpp_path) + include_directory = Path(sys.argv[1]) / "include" + print(str(include_directory)) + for hpp_path in Path(include_directory).rglob(ALL_HPPS): + create_c_header(include_directory, hpp_path) From 03c514362b05447d61da524cd00fe3929902d245 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Tue, 19 Nov 2024 20:13:50 +0000 Subject: [PATCH 28/53] Adds create_deprecated_headers() call after every install() that uses moveit_package() --- moveit_core/CMakeLists.txt | 1 + moveit_kinematics/CMakeLists.txt | 1 + moveit_planners/chomp/chomp_interface/CMakeLists.txt | 1 + moveit_planners/chomp/chomp_motion_planner/CMakeLists.txt | 1 + moveit_planners/ompl/CMakeLists.txt | 1 + moveit_planners/pilz_industrial_motion_planner/CMakeLists.txt | 1 + .../pilz_industrial_motion_planner_testutils/CMakeLists.txt | 1 + moveit_planners/stomp/CMakeLists.txt | 1 + moveit_plugins/moveit_ros_control_interface/CMakeLists.txt | 2 ++ moveit_plugins/moveit_simple_controller_manager/CMakeLists.txt | 1 + moveit_ros/benchmarks/CMakeLists.txt | 2 ++ moveit_ros/hybrid_planning/CMakeLists.txt | 1 + moveit_ros/move_group/CMakeLists.txt | 1 + moveit_ros/moveit_servo/CMakeLists.txt | 1 + moveit_ros/occupancy_map_monitor/CMakeLists.txt | 1 + moveit_ros/perception/CMakeLists.txt | 1 + moveit_ros/planning/CMakeLists.txt | 1 + moveit_ros/planning_interface/CMakeLists.txt | 1 + moveit_ros/robot_interaction/CMakeLists.txt | 1 + moveit_ros/trajectory_cache/CMakeLists.txt | 1 + moveit_ros/visualization/CMakeLists.txt | 1 + moveit_ros/warehouse/CMakeLists.txt | 1 + moveit_setup_assistant/moveit_setup_app_plugins/CMakeLists.txt | 1 + moveit_setup_assistant/moveit_setup_assistant/CMakeLists.txt | 1 + moveit_setup_assistant/moveit_setup_controllers/CMakeLists.txt | 1 + moveit_setup_assistant/moveit_setup_core_plugins/CMakeLists.txt | 1 + moveit_setup_assistant/moveit_setup_framework/CMakeLists.txt | 1 + moveit_setup_assistant/moveit_setup_simulation/CMakeLists.txt | 1 + moveit_setup_assistant/moveit_setup_srdf_plugins/CMakeLists.txt | 1 + 29 files changed, 31 insertions(+) diff --git a/moveit_core/CMakeLists.txt b/moveit_core/CMakeLists.txt index 608babbebc..b91e9b4851 100644 --- a/moveit_core/CMakeLists.txt +++ b/moveit_core/CMakeLists.txt @@ -103,6 +103,7 @@ install( LIBRARY DESTINATION lib ARCHIVE DESTINATION lib RUNTIME DESTINATION bin) +create_deprecated_headers() ament_export_targets(moveit_coreTargets HAS_LIBRARY_TARGET) ament_export_dependencies( diff --git a/moveit_kinematics/CMakeLists.txt b/moveit_kinematics/CMakeLists.txt index 21b03dfb14..c36a47b9fd 100644 --- a/moveit_kinematics/CMakeLists.txt +++ b/moveit_kinematics/CMakeLists.txt @@ -73,6 +73,7 @@ install( RUNTIME DESTINATION bin INCLUDES DESTINATION include/moveit_kinematics) +create_deprecated_headers() ament_export_targets(${PROJECT_NAME}Targets HAS_LIBRARY_TARGET) ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) diff --git a/moveit_planners/chomp/chomp_interface/CMakeLists.txt b/moveit_planners/chomp/chomp_interface/CMakeLists.txt index 3a2c114617..af50dc04c3 100644 --- a/moveit_planners/chomp/chomp_interface/CMakeLists.txt +++ b/moveit_planners/chomp/chomp_interface/CMakeLists.txt @@ -36,6 +36,7 @@ install( LIBRARY DESTINATION lib ARCHIVE DESTINATION lib RUNTIME DESTINATION bin) +create_deprecated_headers() ament_export_targets(moveit_planners_chompTargets HAS_LIBRARY_TARGET) ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) diff --git a/moveit_planners/chomp/chomp_motion_planner/CMakeLists.txt b/moveit_planners/chomp/chomp_motion_planner/CMakeLists.txt index b6407f0e3f..320101e4fe 100644 --- a/moveit_planners/chomp/chomp_motion_planner/CMakeLists.txt +++ b/moveit_planners/chomp/chomp_motion_planner/CMakeLists.txt @@ -34,6 +34,7 @@ install( INCLUDES DESTINATION include/chomp_motion_planner) install(DIRECTORY include/ DESTINATION include/chomp_motion_planner) +create_deprecated_headers() ament_export_targets(chomp_motion_plannerTargets HAS_LIBRARY_TARGET) ament_export_dependencies(${THIS_PACKAGE_EXPORT_DEPENDS}) diff --git a/moveit_planners/ompl/CMakeLists.txt b/moveit_planners/ompl/CMakeLists.txt index 91329a1e8d..032aace4c4 100644 --- a/moveit_planners/ompl/CMakeLists.txt +++ b/moveit_planners/ompl/CMakeLists.txt @@ -41,6 +41,7 @@ install( DESTINATION include/moveit_planners_ompl) ament_export_targets(moveit_planners_omplTargets HAS_LIBRARY_TARGET) ament_export_dependencies(moveit_core ompl) +create_deprecated_headers() pluginlib_export_plugin_description_file(moveit_core ompl_interface_plugin_description.xml) diff --git a/moveit_planners/pilz_industrial_motion_planner/CMakeLists.txt b/moveit_planners/pilz_industrial_motion_planner/CMakeLists.txt index e8420aec32..9f5436d7bc 100644 --- a/moveit_planners/pilz_industrial_motion_planner/CMakeLists.txt +++ b/moveit_planners/pilz_industrial_motion_planner/CMakeLists.txt @@ -164,6 +164,7 @@ install( DESTINATION include/pilz_industrial_motion_planner) install(DIRECTORY include/ DESTINATION include/pilz_industrial_motion_planner) +create_deprecated_headers() ament_export_include_directories(include/pilz_industrial_motion_planner) ament_export_targets(pilz_industrial_motion_plannerTargets HAS_LIBRARY_TARGET) diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/CMakeLists.txt b/moveit_planners/pilz_industrial_motion_planner_testutils/CMakeLists.txt index 1026df76f3..f160edcc62 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/CMakeLists.txt +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/CMakeLists.txt @@ -54,6 +54,7 @@ install( install(DIRECTORY include/ DESTINATION include/pilz_industrial_motion_planner_testutils) +create_deprecated_headers() ament_export_targets(pilz_industrial_motion_planner_testutilsTargets HAS_LIBRARY_TARGET) diff --git a/moveit_planners/stomp/CMakeLists.txt b/moveit_planners/stomp/CMakeLists.txt index 955f227d87..8a2aceb4a4 100644 --- a/moveit_planners/stomp/CMakeLists.txt +++ b/moveit_planners/stomp/CMakeLists.txt @@ -38,6 +38,7 @@ install( RUNTIME DESTINATION bin INCLUDES DESTINATION include/moveit_planners_stomp) +create_deprecated_headers() ament_export_targets(moveit_planners_stompTargets HAS_LIBRARY_TARGET) ament_export_dependencies(moveit_core stomp generate_parameter_library) diff --git a/moveit_plugins/moveit_ros_control_interface/CMakeLists.txt b/moveit_plugins/moveit_ros_control_interface/CMakeLists.txt index 38a203fe27..047301f1b5 100644 --- a/moveit_plugins/moveit_ros_control_interface/CMakeLists.txt +++ b/moveit_plugins/moveit_ros_control_interface/CMakeLists.txt @@ -80,6 +80,8 @@ install( # Mark cpp header files for installation install(DIRECTORY include/ DESTINATION include/moveit_ros_control_interface) +create_deprecated_headers() + pluginlib_export_plugin_description_file(moveit_core moveit_core_plugins.xml) pluginlib_export_plugin_description_file( moveit_ros_control_interface moveit_ros_control_interface_plugins.xml) diff --git a/moveit_plugins/moveit_simple_controller_manager/CMakeLists.txt b/moveit_plugins/moveit_simple_controller_manager/CMakeLists.txt index 9905ae3238..cd9faaa570 100644 --- a/moveit_plugins/moveit_simple_controller_manager/CMakeLists.txt +++ b/moveit_plugins/moveit_simple_controller_manager/CMakeLists.txt @@ -41,6 +41,7 @@ install( INCLUDES DESTINATION include/moveit_simple_controller_manager) install(DIRECTORY include/ DESTINATION include/moveit_simple_controller_manager) +create_deprecated_headers() ament_export_targets(moveit_simple_controller_managerTargets HAS_LIBRARY_TARGET) ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS} Boost) diff --git a/moveit_ros/benchmarks/CMakeLists.txt b/moveit_ros/benchmarks/CMakeLists.txt index 58538a70b9..e2515a2d00 100644 --- a/moveit_ros/benchmarks/CMakeLists.txt +++ b/moveit_ros/benchmarks/CMakeLists.txt @@ -60,4 +60,6 @@ install(DIRECTORY include/ DESTINATION include/moveit_ros_benchmarks) install(PROGRAMS scripts/moveit_benchmark_statistics.py DESTINATION lib/moveit_ros_benchmarks) +create_deprecated_headers() + ament_package(CONFIG_EXTRAS ConfigExtras.cmake) diff --git a/moveit_ros/hybrid_planning/CMakeLists.txt b/moveit_ros/hybrid_planning/CMakeLists.txt index 0f90c56033..1124f26760 100644 --- a/moveit_ros/hybrid_planning/CMakeLists.txt +++ b/moveit_ros/hybrid_planning/CMakeLists.txt @@ -97,6 +97,7 @@ install(DIRECTORY ${THIS_PACKAGE_INCLUDE_DIRS} install(DIRECTORY test/launch DESTINATION share/moveit_hybrid_planning) install(DIRECTORY test/config DESTINATION share/moveit_hybrid_planning) +create_deprecated_headers() pluginlib_export_plugin_description_file(moveit_hybrid_planning single_plan_execution_plugin.xml) diff --git a/moveit_ros/move_group/CMakeLists.txt b/moveit_ros/move_group/CMakeLists.txt index bd48293e7a..ae12724df1 100644 --- a/moveit_ros/move_group/CMakeLists.txt +++ b/moveit_ros/move_group/CMakeLists.txt @@ -90,6 +90,7 @@ install(DIRECTORY include/ DESTINATION include/moveit_ros_move_group) install(PROGRAMS scripts/load_map scripts/save_map DESTINATION lib/moveit_ros_move_group) +create_deprecated_headers() pluginlib_export_plugin_description_file( moveit_ros_move_group default_capabilities_plugin_description.xml) diff --git a/moveit_ros/moveit_servo/CMakeLists.txt b/moveit_ros/moveit_servo/CMakeLists.txt index 6ec080d195..eca5b7aa47 100644 --- a/moveit_ros/moveit_servo/CMakeLists.txt +++ b/moveit_ros/moveit_servo/CMakeLists.txt @@ -110,6 +110,7 @@ install( install(DIRECTORY include/ DESTINATION include/moveit_servo) install(DIRECTORY launch DESTINATION share/moveit_servo) install(DIRECTORY config DESTINATION share/moveit_servo) +create_deprecated_headers() ament_export_targets(moveit_servoTargets HAS_LIBRARY_TARGET) ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) diff --git a/moveit_ros/occupancy_map_monitor/CMakeLists.txt b/moveit_ros/occupancy_map_monitor/CMakeLists.txt index b8dd549bcb..434be25937 100644 --- a/moveit_ros/occupancy_map_monitor/CMakeLists.txt +++ b/moveit_ros/occupancy_map_monitor/CMakeLists.txt @@ -59,6 +59,7 @@ install( install(TARGETS moveit_ros_occupancy_map_server DESTINATION lib/moveit_ros_occupancy_map_monitor) install(DIRECTORY include/ DESTINATION include/moveit_ros_occupancy_map_monitor) +create_deprecated_headers() ament_export_targets(moveit_ros_occupancy_map_monitorTargets HAS_LIBRARY_TARGET) ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS} eigen3_cmake_module) diff --git a/moveit_ros/perception/CMakeLists.txt b/moveit_ros/perception/CMakeLists.txt index 0452e04858..165b34d4ac 100644 --- a/moveit_ros/perception/CMakeLists.txt +++ b/moveit_ros/perception/CMakeLists.txt @@ -112,6 +112,7 @@ install( RUNTIME DESTINATION bin INCLUDES DESTINATION include/moveit_ros_perception) +create_deprecated_headers() ament_export_targets(moveit_ros_perceptionTargets HAS_LIBRARY_TARGET) ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) diff --git a/moveit_ros/planning/CMakeLists.txt b/moveit_ros/planning/CMakeLists.txt index 9b4136d012..94ea0dd41d 100644 --- a/moveit_ros/planning/CMakeLists.txt +++ b/moveit_ros/planning/CMakeLists.txt @@ -118,6 +118,7 @@ install( RUNTIME DESTINATION bin INCLUDES DESTINATION include/moveit_ros_planning) +create_deprecated_headers() ament_export_targets(moveit_ros_planningTargets HAS_LIBRARY_TARGET) ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) diff --git a/moveit_ros/planning_interface/CMakeLists.txt b/moveit_ros/planning_interface/CMakeLists.txt index 47470e0a76..3865bde74f 100644 --- a/moveit_ros/planning_interface/CMakeLists.txt +++ b/moveit_ros/planning_interface/CMakeLists.txt @@ -82,6 +82,7 @@ install( RUNTIME DESTINATION bin INCLUDES DESTINATION include/moveit_ros_planning_interface) +create_deprecated_headers() ament_export_targets(moveit_ros_planning_interfaceTargets HAS_LIBRARY_TARGET) ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) diff --git a/moveit_ros/robot_interaction/CMakeLists.txt b/moveit_ros/robot_interaction/CMakeLists.txt index c9140d2a4f..fe2862f269 100644 --- a/moveit_ros/robot_interaction/CMakeLists.txt +++ b/moveit_ros/robot_interaction/CMakeLists.txt @@ -55,6 +55,7 @@ install(FILES ${CMAKE_CURRENT_BINARY_DIR}/moveit_robot_interaction_export.h DESTINATION include/moveit_ros_robot_interaction) install(DIRECTORY resources DESTINATION share/moveit_ros_robot_interaction) +create_deprecated_headers() ament_export_targets(moveit_ros_robot_interactionTargets HAS_LIBRARY_TARGET) ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) diff --git a/moveit_ros/trajectory_cache/CMakeLists.txt b/moveit_ros/trajectory_cache/CMakeLists.txt index d013111c53..09811bd956 100644 --- a/moveit_ros/trajectory_cache/CMakeLists.txt +++ b/moveit_ros/trajectory_cache/CMakeLists.txt @@ -51,6 +51,7 @@ install(DIRECTORY include/ DESTINATION include/moveit_ros_trajectory_cache) install( FILES ${CMAKE_CURRENT_BINARY_DIR}/moveit_ros_trajectory_cache_lib_export.h DESTINATION include/moveit_ros_trajectory_cache) +create_deprecated_headers() if(BUILD_TESTING) find_package(ament_cmake_pytest REQUIRED) diff --git a/moveit_ros/visualization/CMakeLists.txt b/moveit_ros/visualization/CMakeLists.txt index 27855877a3..4b1a18c2cc 100644 --- a/moveit_ros/visualization/CMakeLists.txt +++ b/moveit_ros/visualization/CMakeLists.txt @@ -114,6 +114,7 @@ install( RUNTIME DESTINATION bin INCLUDES DESTINATION include/moveit_ros_visualization) +create_deprecated_headers() ament_export_targets(moveit_ros_visualizationTargets HAS_LIBRARY_TARGET) ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) diff --git a/moveit_ros/warehouse/CMakeLists.txt b/moveit_ros/warehouse/CMakeLists.txt index 825f6b11c7..cf29a2c391 100644 --- a/moveit_ros/warehouse/CMakeLists.txt +++ b/moveit_ros/warehouse/CMakeLists.txt @@ -95,6 +95,7 @@ install( RUNTIME DESTINATION bin INCLUDES DESTINATION include/moveit_ros_warehouse) +create_deprecated_headers() ament_export_targets(moveit_ros_warehouseTargets HAS_LIBRARY_TARGET) ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/CMakeLists.txt b/moveit_setup_assistant/moveit_setup_app_plugins/CMakeLists.txt index fb10aca607..854e3bc26d 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/CMakeLists.txt +++ b/moveit_setup_assistant/moveit_setup_app_plugins/CMakeLists.txt @@ -56,6 +56,7 @@ install( install(FILES moveit_setup_framework_plugins.xml DESTINATION share/moveit_setup_app_plugins) install(DIRECTORY include/ DESTINATION include/moveit_setup_app_plugins) +create_deprecated_headers() ament_export_targets(moveit_setup_app_pluginsTargets HAS_LIBRARY_TARGET) pluginlib_export_plugin_description_file(moveit_setup_framework diff --git a/moveit_setup_assistant/moveit_setup_assistant/CMakeLists.txt b/moveit_setup_assistant/moveit_setup_assistant/CMakeLists.txt index e7c69dcc92..d3480e4278 100644 --- a/moveit_setup_assistant/moveit_setup_assistant/CMakeLists.txt +++ b/moveit_setup_assistant/moveit_setup_assistant/CMakeLists.txt @@ -66,6 +66,7 @@ install( INCLUDES DESTINATION include/moveit_setup_assistant) install(DIRECTORY include/ DESTINATION include/moveit_setup_assistant) +create_deprecated_headers() ament_export_include_directories(include) install(DIRECTORY launch DESTINATION share/moveit_setup_assistant) install(DIRECTORY resources DESTINATION share/moveit_setup_assistant) diff --git a/moveit_setup_assistant/moveit_setup_controllers/CMakeLists.txt b/moveit_setup_assistant/moveit_setup_controllers/CMakeLists.txt index 3e661098ba..965a242af6 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/CMakeLists.txt +++ b/moveit_setup_assistant/moveit_setup_controllers/CMakeLists.txt @@ -63,6 +63,7 @@ install(FILES moveit_setup_framework_plugins.xml DESTINATION share/moveit_setup_controllers) install(DIRECTORY include/ DESTINATION include/moveit_setup_controllers) install(DIRECTORY launch DESTINATION share/moveit_setup_controllers) +create_deprecated_headers() ament_export_targets(moveit_setup_controllersTargets HAS_LIBRARY_TARGET) pluginlib_export_plugin_description_file(moveit_setup_framework diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/CMakeLists.txt b/moveit_setup_assistant/moveit_setup_core_plugins/CMakeLists.txt index 2610a37ea4..0a235dd6dd 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/CMakeLists.txt +++ b/moveit_setup_assistant/moveit_setup_core_plugins/CMakeLists.txt @@ -57,6 +57,7 @@ install( install(FILES moveit_setup_framework_plugins.xml DESTINATION share/${PROJECT_NAME}) install(DIRECTORY include/ DESTINATION include/moveit_setup_core_plugins) +create_deprecated_headers() ament_export_targets(moveit_setup_core_pluginsTargets HAS_LIBRARY_TARGET) pluginlib_export_plugin_description_file(moveit_setup_framework diff --git a/moveit_setup_assistant/moveit_setup_framework/CMakeLists.txt b/moveit_setup_assistant/moveit_setup_framework/CMakeLists.txt index 3e3d417fbc..9e441ee459 100644 --- a/moveit_setup_assistant/moveit_setup_framework/CMakeLists.txt +++ b/moveit_setup_assistant/moveit_setup_framework/CMakeLists.txt @@ -67,6 +67,7 @@ install(FILES moveit_setup_framework_plugins.xml DESTINATION share/moveit_setup_framework) install(DIRECTORY templates DESTINATION share/moveit_setup_framework) +create_deprecated_headers() ament_export_targets(moveit_setup_frameworkTargets HAS_LIBRARY_TARGET) install( diff --git a/moveit_setup_assistant/moveit_setup_simulation/CMakeLists.txt b/moveit_setup_assistant/moveit_setup_simulation/CMakeLists.txt index 127b1e408f..8b5ed7a848 100644 --- a/moveit_setup_assistant/moveit_setup_simulation/CMakeLists.txt +++ b/moveit_setup_assistant/moveit_setup_simulation/CMakeLists.txt @@ -40,6 +40,7 @@ install( install(FILES moveit_setup_framework_plugins.xml DESTINATION share/moveit_setup_simulation) install(DIRECTORY include/ DESTINATION include/moveit_setup_simulation) +create_deprecated_headers() ament_export_targets(moveit_setup_simulationTargets HAS_LIBRARY_TARGET) pluginlib_export_plugin_description_file(moveit_setup_framework diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/CMakeLists.txt b/moveit_setup_assistant/moveit_setup_srdf_plugins/CMakeLists.txt index 6e34b6346b..cf93312033 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/CMakeLists.txt +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/CMakeLists.txt @@ -70,6 +70,7 @@ install( install(FILES moveit_setup_framework_plugins.xml DESTINATION share/moveit_setup_srdf_plugins) install(DIRECTORY include/ DESTINATION include/moveit_setup_srdf_plugins) +create_deprecated_headers() ament_export_targets(moveit_setup_srdf_pluginsTargets HAS_LIBRARY_TARGET) pluginlib_export_plugin_description_file(moveit_setup_framework From a59cd5755da50a681d337b2a6f2e3a3002023078 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Tue, 19 Nov 2024 20:24:27 +0000 Subject: [PATCH 29/53] Fixes formatting --- moveit_common/cmake/deprecated_headers.cmake | 11 +++++++---- moveit_common/scripts/create_deprecated_headers.py | 1 + 2 files changed, 8 insertions(+), 4 deletions(-) diff --git a/moveit_common/cmake/deprecated_headers.cmake b/moveit_common/cmake/deprecated_headers.cmake index a53ff9db6f..54200701a2 100644 --- a/moveit_common/cmake/deprecated_headers.cmake +++ b/moveit_common/cmake/deprecated_headers.cmake @@ -30,8 +30,11 @@ find_package(Python REQUIRED) set(SCRIPT ${CMAKE_CURRENT_LIST_DIR}/../scripts/create_deprecated_headers.py) +# Run after all install() commands in a moveit_package() CMakeLists.txt to +# generate .h files for every .hpp macro(CREATE_DEPRECATED_HEADERS) - add_custom_target(${PROJECT_NAME}_deprecated_headers ALL - COMMAND ${PYTHON_EXECUTABLE} ${SCRIPT} ${CMAKE_INSTALL_PREFIX} - ) -endmacro() \ No newline at end of file + add_custom_target( + ${PROJECT_NAME}_deprecated_headers ALL + COMMAND ${PYTHON_EXECUTABLE} ${SCRIPT} ${CMAKE_INSTALL_PREFIX} + COMMENT "Autogenerating deprecated .h files for ${PROJECT_NAME}") +endmacro() diff --git a/moveit_common/scripts/create_deprecated_headers.py b/moveit_common/scripts/create_deprecated_headers.py index 5029138742..c4563a915d 100755 --- a/moveit_common/scripts/create_deprecated_headers.py +++ b/moveit_common/scripts/create_deprecated_headers.py @@ -36,6 +36,7 @@ USAGE = "Usage: ./generate_deprecated_headers " DEPRECATION = "{0}.h imports are deprecated. Consider using {0}.hpp" + def create_c_header(include_directory: Path, hpp_path: Path) -> None: file = hpp_path.name.replace(".hpp", "") hpp_import = f"<{hpp_path.relative_to(include_directory)}>" From bf11b687d44be3269f30d087cf2d9b8c54f82bda Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Tue, 19 Nov 2024 20:41:41 +0000 Subject: [PATCH 30/53] Fixes script --- moveit_common/scripts/create_deprecated_headers.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/moveit_common/scripts/create_deprecated_headers.py b/moveit_common/scripts/create_deprecated_headers.py index c4563a915d..3bc89134a6 100755 --- a/moveit_common/scripts/create_deprecated_headers.py +++ b/moveit_common/scripts/create_deprecated_headers.py @@ -40,7 +40,7 @@ def create_c_header(include_directory: Path, hpp_path: Path) -> None: file = hpp_path.name.replace(".hpp", "") hpp_import = f"<{hpp_path.relative_to(include_directory)}>" - with open(str(hpp_path).replace("pp", ""), "w") as h_file: + with open(str(hpp_path).replace(".hpp", ".h"), "w") as h_file: h_file.write(f"#warning {DEPRECATION.format(file)}\n") h_file.write(f"#include {hpp_import}\n") From 71efe77695876f592f8a710296d0c62fec07902e Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Tue, 19 Nov 2024 20:43:50 +0000 Subject: [PATCH 31/53] Simplifies script --- moveit_common/scripts/create_deprecated_headers.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/moveit_common/scripts/create_deprecated_headers.py b/moveit_common/scripts/create_deprecated_headers.py index 3bc89134a6..a119b2631a 100755 --- a/moveit_common/scripts/create_deprecated_headers.py +++ b/moveit_common/scripts/create_deprecated_headers.py @@ -40,7 +40,7 @@ def create_c_header(include_directory: Path, hpp_path: Path) -> None: file = hpp_path.name.replace(".hpp", "") hpp_import = f"<{hpp_path.relative_to(include_directory)}>" - with open(str(hpp_path).replace(".hpp", ".h"), "w") as h_file: + with open(hpp_path.with_suffix(".h"), "w") as h_file: h_file.write(f"#warning {DEPRECATION.format(file)}\n") h_file.write(f"#include {hpp_import}\n") From 939f24f2f35824bfeaed5122dcadd091d0e24ad3 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Thu, 21 Nov 2024 11:30:12 +0000 Subject: [PATCH 32/53] Removes create_deprecated_headers() macro calls --- moveit_common/cmake/deprecated_headers.cmake | 5 +++-- moveit_core/CMakeLists.txt | 1 - moveit_kinematics/CMakeLists.txt | 1 - moveit_planners/chomp/chomp_interface/CMakeLists.txt | 1 - moveit_planners/chomp/chomp_motion_planner/CMakeLists.txt | 1 - moveit_planners/ompl/CMakeLists.txt | 1 - .../pilz_industrial_motion_planner/CMakeLists.txt | 1 - .../pilz_industrial_motion_planner_testutils/CMakeLists.txt | 1 - moveit_planners/stomp/CMakeLists.txt | 1 - moveit_plugins/moveit_ros_control_interface/CMakeLists.txt | 2 -- .../moveit_simple_controller_manager/CMakeLists.txt | 1 - moveit_ros/benchmarks/CMakeLists.txt | 2 -- moveit_ros/hybrid_planning/CMakeLists.txt | 1 - moveit_ros/move_group/CMakeLists.txt | 1 - moveit_ros/moveit_servo/CMakeLists.txt | 1 - moveit_ros/occupancy_map_monitor/CMakeLists.txt | 1 - moveit_ros/perception/CMakeLists.txt | 1 - moveit_ros/planning/CMakeLists.txt | 1 - moveit_ros/planning_interface/CMakeLists.txt | 1 - moveit_ros/robot_interaction/CMakeLists.txt | 1 - moveit_ros/trajectory_cache/CMakeLists.txt | 1 - moveit_ros/visualization/CMakeLists.txt | 1 - moveit_ros/warehouse/CMakeLists.txt | 1 - .../moveit_setup_app_plugins/CMakeLists.txt | 1 - moveit_setup_assistant/moveit_setup_assistant/CMakeLists.txt | 2 +- .../moveit_setup_controllers/CMakeLists.txt | 1 - .../moveit_setup_core_plugins/CMakeLists.txt | 1 - moveit_setup_assistant/moveit_setup_framework/CMakeLists.txt | 1 - .../moveit_setup_simulation/CMakeLists.txt | 1 - .../moveit_setup_srdf_plugins/CMakeLists.txt | 1 - 30 files changed, 4 insertions(+), 33 deletions(-) diff --git a/moveit_common/cmake/deprecated_headers.cmake b/moveit_common/cmake/deprecated_headers.cmake index 54200701a2..6d0622b844 100644 --- a/moveit_common/cmake/deprecated_headers.cmake +++ b/moveit_common/cmake/deprecated_headers.cmake @@ -30,8 +30,9 @@ find_package(Python REQUIRED) set(SCRIPT ${CMAKE_CURRENT_LIST_DIR}/../scripts/create_deprecated_headers.py) -# Run after all install() commands in a moveit_package() CMakeLists.txt to -# generate .h files for every .hpp +# Run to generate deprecated c headers for every .hpp in the local install space +# Note: This is currently unused. See: +# https://github.com/moveit/moveit2/pull/3113 macro(CREATE_DEPRECATED_HEADERS) add_custom_target( ${PROJECT_NAME}_deprecated_headers ALL diff --git a/moveit_core/CMakeLists.txt b/moveit_core/CMakeLists.txt index b91e9b4851..608babbebc 100644 --- a/moveit_core/CMakeLists.txt +++ b/moveit_core/CMakeLists.txt @@ -103,7 +103,6 @@ install( LIBRARY DESTINATION lib ARCHIVE DESTINATION lib RUNTIME DESTINATION bin) -create_deprecated_headers() ament_export_targets(moveit_coreTargets HAS_LIBRARY_TARGET) ament_export_dependencies( diff --git a/moveit_kinematics/CMakeLists.txt b/moveit_kinematics/CMakeLists.txt index c36a47b9fd..21b03dfb14 100644 --- a/moveit_kinematics/CMakeLists.txt +++ b/moveit_kinematics/CMakeLists.txt @@ -73,7 +73,6 @@ install( RUNTIME DESTINATION bin INCLUDES DESTINATION include/moveit_kinematics) -create_deprecated_headers() ament_export_targets(${PROJECT_NAME}Targets HAS_LIBRARY_TARGET) ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) diff --git a/moveit_planners/chomp/chomp_interface/CMakeLists.txt b/moveit_planners/chomp/chomp_interface/CMakeLists.txt index af50dc04c3..3a2c114617 100644 --- a/moveit_planners/chomp/chomp_interface/CMakeLists.txt +++ b/moveit_planners/chomp/chomp_interface/CMakeLists.txt @@ -36,7 +36,6 @@ install( LIBRARY DESTINATION lib ARCHIVE DESTINATION lib RUNTIME DESTINATION bin) -create_deprecated_headers() ament_export_targets(moveit_planners_chompTargets HAS_LIBRARY_TARGET) ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) diff --git a/moveit_planners/chomp/chomp_motion_planner/CMakeLists.txt b/moveit_planners/chomp/chomp_motion_planner/CMakeLists.txt index 320101e4fe..b6407f0e3f 100644 --- a/moveit_planners/chomp/chomp_motion_planner/CMakeLists.txt +++ b/moveit_planners/chomp/chomp_motion_planner/CMakeLists.txt @@ -34,7 +34,6 @@ install( INCLUDES DESTINATION include/chomp_motion_planner) install(DIRECTORY include/ DESTINATION include/chomp_motion_planner) -create_deprecated_headers() ament_export_targets(chomp_motion_plannerTargets HAS_LIBRARY_TARGET) ament_export_dependencies(${THIS_PACKAGE_EXPORT_DEPENDS}) diff --git a/moveit_planners/ompl/CMakeLists.txt b/moveit_planners/ompl/CMakeLists.txt index 032aace4c4..91329a1e8d 100644 --- a/moveit_planners/ompl/CMakeLists.txt +++ b/moveit_planners/ompl/CMakeLists.txt @@ -41,7 +41,6 @@ install( DESTINATION include/moveit_planners_ompl) ament_export_targets(moveit_planners_omplTargets HAS_LIBRARY_TARGET) ament_export_dependencies(moveit_core ompl) -create_deprecated_headers() pluginlib_export_plugin_description_file(moveit_core ompl_interface_plugin_description.xml) diff --git a/moveit_planners/pilz_industrial_motion_planner/CMakeLists.txt b/moveit_planners/pilz_industrial_motion_planner/CMakeLists.txt index 9f5436d7bc..e8420aec32 100644 --- a/moveit_planners/pilz_industrial_motion_planner/CMakeLists.txt +++ b/moveit_planners/pilz_industrial_motion_planner/CMakeLists.txt @@ -164,7 +164,6 @@ install( DESTINATION include/pilz_industrial_motion_planner) install(DIRECTORY include/ DESTINATION include/pilz_industrial_motion_planner) -create_deprecated_headers() ament_export_include_directories(include/pilz_industrial_motion_planner) ament_export_targets(pilz_industrial_motion_plannerTargets HAS_LIBRARY_TARGET) diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/CMakeLists.txt b/moveit_planners/pilz_industrial_motion_planner_testutils/CMakeLists.txt index f160edcc62..1026df76f3 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/CMakeLists.txt +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/CMakeLists.txt @@ -54,7 +54,6 @@ install( install(DIRECTORY include/ DESTINATION include/pilz_industrial_motion_planner_testutils) -create_deprecated_headers() ament_export_targets(pilz_industrial_motion_planner_testutilsTargets HAS_LIBRARY_TARGET) diff --git a/moveit_planners/stomp/CMakeLists.txt b/moveit_planners/stomp/CMakeLists.txt index 8a2aceb4a4..955f227d87 100644 --- a/moveit_planners/stomp/CMakeLists.txt +++ b/moveit_planners/stomp/CMakeLists.txt @@ -38,7 +38,6 @@ install( RUNTIME DESTINATION bin INCLUDES DESTINATION include/moveit_planners_stomp) -create_deprecated_headers() ament_export_targets(moveit_planners_stompTargets HAS_LIBRARY_TARGET) ament_export_dependencies(moveit_core stomp generate_parameter_library) diff --git a/moveit_plugins/moveit_ros_control_interface/CMakeLists.txt b/moveit_plugins/moveit_ros_control_interface/CMakeLists.txt index 047301f1b5..38a203fe27 100644 --- a/moveit_plugins/moveit_ros_control_interface/CMakeLists.txt +++ b/moveit_plugins/moveit_ros_control_interface/CMakeLists.txt @@ -80,8 +80,6 @@ install( # Mark cpp header files for installation install(DIRECTORY include/ DESTINATION include/moveit_ros_control_interface) -create_deprecated_headers() - pluginlib_export_plugin_description_file(moveit_core moveit_core_plugins.xml) pluginlib_export_plugin_description_file( moveit_ros_control_interface moveit_ros_control_interface_plugins.xml) diff --git a/moveit_plugins/moveit_simple_controller_manager/CMakeLists.txt b/moveit_plugins/moveit_simple_controller_manager/CMakeLists.txt index cd9faaa570..9905ae3238 100644 --- a/moveit_plugins/moveit_simple_controller_manager/CMakeLists.txt +++ b/moveit_plugins/moveit_simple_controller_manager/CMakeLists.txt @@ -41,7 +41,6 @@ install( INCLUDES DESTINATION include/moveit_simple_controller_manager) install(DIRECTORY include/ DESTINATION include/moveit_simple_controller_manager) -create_deprecated_headers() ament_export_targets(moveit_simple_controller_managerTargets HAS_LIBRARY_TARGET) ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS} Boost) diff --git a/moveit_ros/benchmarks/CMakeLists.txt b/moveit_ros/benchmarks/CMakeLists.txt index e2515a2d00..58538a70b9 100644 --- a/moveit_ros/benchmarks/CMakeLists.txt +++ b/moveit_ros/benchmarks/CMakeLists.txt @@ -60,6 +60,4 @@ install(DIRECTORY include/ DESTINATION include/moveit_ros_benchmarks) install(PROGRAMS scripts/moveit_benchmark_statistics.py DESTINATION lib/moveit_ros_benchmarks) -create_deprecated_headers() - ament_package(CONFIG_EXTRAS ConfigExtras.cmake) diff --git a/moveit_ros/hybrid_planning/CMakeLists.txt b/moveit_ros/hybrid_planning/CMakeLists.txt index 1124f26760..0f90c56033 100644 --- a/moveit_ros/hybrid_planning/CMakeLists.txt +++ b/moveit_ros/hybrid_planning/CMakeLists.txt @@ -97,7 +97,6 @@ install(DIRECTORY ${THIS_PACKAGE_INCLUDE_DIRS} install(DIRECTORY test/launch DESTINATION share/moveit_hybrid_planning) install(DIRECTORY test/config DESTINATION share/moveit_hybrid_planning) -create_deprecated_headers() pluginlib_export_plugin_description_file(moveit_hybrid_planning single_plan_execution_plugin.xml) diff --git a/moveit_ros/move_group/CMakeLists.txt b/moveit_ros/move_group/CMakeLists.txt index ae12724df1..bd48293e7a 100644 --- a/moveit_ros/move_group/CMakeLists.txt +++ b/moveit_ros/move_group/CMakeLists.txt @@ -90,7 +90,6 @@ install(DIRECTORY include/ DESTINATION include/moveit_ros_move_group) install(PROGRAMS scripts/load_map scripts/save_map DESTINATION lib/moveit_ros_move_group) -create_deprecated_headers() pluginlib_export_plugin_description_file( moveit_ros_move_group default_capabilities_plugin_description.xml) diff --git a/moveit_ros/moveit_servo/CMakeLists.txt b/moveit_ros/moveit_servo/CMakeLists.txt index eca5b7aa47..6ec080d195 100644 --- a/moveit_ros/moveit_servo/CMakeLists.txt +++ b/moveit_ros/moveit_servo/CMakeLists.txt @@ -110,7 +110,6 @@ install( install(DIRECTORY include/ DESTINATION include/moveit_servo) install(DIRECTORY launch DESTINATION share/moveit_servo) install(DIRECTORY config DESTINATION share/moveit_servo) -create_deprecated_headers() ament_export_targets(moveit_servoTargets HAS_LIBRARY_TARGET) ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) diff --git a/moveit_ros/occupancy_map_monitor/CMakeLists.txt b/moveit_ros/occupancy_map_monitor/CMakeLists.txt index 434be25937..b8dd549bcb 100644 --- a/moveit_ros/occupancy_map_monitor/CMakeLists.txt +++ b/moveit_ros/occupancy_map_monitor/CMakeLists.txt @@ -59,7 +59,6 @@ install( install(TARGETS moveit_ros_occupancy_map_server DESTINATION lib/moveit_ros_occupancy_map_monitor) install(DIRECTORY include/ DESTINATION include/moveit_ros_occupancy_map_monitor) -create_deprecated_headers() ament_export_targets(moveit_ros_occupancy_map_monitorTargets HAS_LIBRARY_TARGET) ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS} eigen3_cmake_module) diff --git a/moveit_ros/perception/CMakeLists.txt b/moveit_ros/perception/CMakeLists.txt index 165b34d4ac..0452e04858 100644 --- a/moveit_ros/perception/CMakeLists.txt +++ b/moveit_ros/perception/CMakeLists.txt @@ -112,7 +112,6 @@ install( RUNTIME DESTINATION bin INCLUDES DESTINATION include/moveit_ros_perception) -create_deprecated_headers() ament_export_targets(moveit_ros_perceptionTargets HAS_LIBRARY_TARGET) ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) diff --git a/moveit_ros/planning/CMakeLists.txt b/moveit_ros/planning/CMakeLists.txt index 94ea0dd41d..9b4136d012 100644 --- a/moveit_ros/planning/CMakeLists.txt +++ b/moveit_ros/planning/CMakeLists.txt @@ -118,7 +118,6 @@ install( RUNTIME DESTINATION bin INCLUDES DESTINATION include/moveit_ros_planning) -create_deprecated_headers() ament_export_targets(moveit_ros_planningTargets HAS_LIBRARY_TARGET) ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) diff --git a/moveit_ros/planning_interface/CMakeLists.txt b/moveit_ros/planning_interface/CMakeLists.txt index 3865bde74f..47470e0a76 100644 --- a/moveit_ros/planning_interface/CMakeLists.txt +++ b/moveit_ros/planning_interface/CMakeLists.txt @@ -82,7 +82,6 @@ install( RUNTIME DESTINATION bin INCLUDES DESTINATION include/moveit_ros_planning_interface) -create_deprecated_headers() ament_export_targets(moveit_ros_planning_interfaceTargets HAS_LIBRARY_TARGET) ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) diff --git a/moveit_ros/robot_interaction/CMakeLists.txt b/moveit_ros/robot_interaction/CMakeLists.txt index fe2862f269..c9140d2a4f 100644 --- a/moveit_ros/robot_interaction/CMakeLists.txt +++ b/moveit_ros/robot_interaction/CMakeLists.txt @@ -55,7 +55,6 @@ install(FILES ${CMAKE_CURRENT_BINARY_DIR}/moveit_robot_interaction_export.h DESTINATION include/moveit_ros_robot_interaction) install(DIRECTORY resources DESTINATION share/moveit_ros_robot_interaction) -create_deprecated_headers() ament_export_targets(moveit_ros_robot_interactionTargets HAS_LIBRARY_TARGET) ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) diff --git a/moveit_ros/trajectory_cache/CMakeLists.txt b/moveit_ros/trajectory_cache/CMakeLists.txt index 09811bd956..d013111c53 100644 --- a/moveit_ros/trajectory_cache/CMakeLists.txt +++ b/moveit_ros/trajectory_cache/CMakeLists.txt @@ -51,7 +51,6 @@ install(DIRECTORY include/ DESTINATION include/moveit_ros_trajectory_cache) install( FILES ${CMAKE_CURRENT_BINARY_DIR}/moveit_ros_trajectory_cache_lib_export.h DESTINATION include/moveit_ros_trajectory_cache) -create_deprecated_headers() if(BUILD_TESTING) find_package(ament_cmake_pytest REQUIRED) diff --git a/moveit_ros/visualization/CMakeLists.txt b/moveit_ros/visualization/CMakeLists.txt index 4b1a18c2cc..27855877a3 100644 --- a/moveit_ros/visualization/CMakeLists.txt +++ b/moveit_ros/visualization/CMakeLists.txt @@ -114,7 +114,6 @@ install( RUNTIME DESTINATION bin INCLUDES DESTINATION include/moveit_ros_visualization) -create_deprecated_headers() ament_export_targets(moveit_ros_visualizationTargets HAS_LIBRARY_TARGET) ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) diff --git a/moveit_ros/warehouse/CMakeLists.txt b/moveit_ros/warehouse/CMakeLists.txt index cf29a2c391..825f6b11c7 100644 --- a/moveit_ros/warehouse/CMakeLists.txt +++ b/moveit_ros/warehouse/CMakeLists.txt @@ -95,7 +95,6 @@ install( RUNTIME DESTINATION bin INCLUDES DESTINATION include/moveit_ros_warehouse) -create_deprecated_headers() ament_export_targets(moveit_ros_warehouseTargets HAS_LIBRARY_TARGET) ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/CMakeLists.txt b/moveit_setup_assistant/moveit_setup_app_plugins/CMakeLists.txt index 854e3bc26d..fb10aca607 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/CMakeLists.txt +++ b/moveit_setup_assistant/moveit_setup_app_plugins/CMakeLists.txt @@ -56,7 +56,6 @@ install( install(FILES moveit_setup_framework_plugins.xml DESTINATION share/moveit_setup_app_plugins) install(DIRECTORY include/ DESTINATION include/moveit_setup_app_plugins) -create_deprecated_headers() ament_export_targets(moveit_setup_app_pluginsTargets HAS_LIBRARY_TARGET) pluginlib_export_plugin_description_file(moveit_setup_framework diff --git a/moveit_setup_assistant/moveit_setup_assistant/CMakeLists.txt b/moveit_setup_assistant/moveit_setup_assistant/CMakeLists.txt index d3480e4278..6dc113eab1 100644 --- a/moveit_setup_assistant/moveit_setup_assistant/CMakeLists.txt +++ b/moveit_setup_assistant/moveit_setup_assistant/CMakeLists.txt @@ -66,7 +66,7 @@ install( INCLUDES DESTINATION include/moveit_setup_assistant) install(DIRECTORY include/ DESTINATION include/moveit_setup_assistant) -create_deprecated_headers() + ament_export_include_directories(include) install(DIRECTORY launch DESTINATION share/moveit_setup_assistant) install(DIRECTORY resources DESTINATION share/moveit_setup_assistant) diff --git a/moveit_setup_assistant/moveit_setup_controllers/CMakeLists.txt b/moveit_setup_assistant/moveit_setup_controllers/CMakeLists.txt index 965a242af6..3e661098ba 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/CMakeLists.txt +++ b/moveit_setup_assistant/moveit_setup_controllers/CMakeLists.txt @@ -63,7 +63,6 @@ install(FILES moveit_setup_framework_plugins.xml DESTINATION share/moveit_setup_controllers) install(DIRECTORY include/ DESTINATION include/moveit_setup_controllers) install(DIRECTORY launch DESTINATION share/moveit_setup_controllers) -create_deprecated_headers() ament_export_targets(moveit_setup_controllersTargets HAS_LIBRARY_TARGET) pluginlib_export_plugin_description_file(moveit_setup_framework diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/CMakeLists.txt b/moveit_setup_assistant/moveit_setup_core_plugins/CMakeLists.txt index 0a235dd6dd..2610a37ea4 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/CMakeLists.txt +++ b/moveit_setup_assistant/moveit_setup_core_plugins/CMakeLists.txt @@ -57,7 +57,6 @@ install( install(FILES moveit_setup_framework_plugins.xml DESTINATION share/${PROJECT_NAME}) install(DIRECTORY include/ DESTINATION include/moveit_setup_core_plugins) -create_deprecated_headers() ament_export_targets(moveit_setup_core_pluginsTargets HAS_LIBRARY_TARGET) pluginlib_export_plugin_description_file(moveit_setup_framework diff --git a/moveit_setup_assistant/moveit_setup_framework/CMakeLists.txt b/moveit_setup_assistant/moveit_setup_framework/CMakeLists.txt index 9e441ee459..3e3d417fbc 100644 --- a/moveit_setup_assistant/moveit_setup_framework/CMakeLists.txt +++ b/moveit_setup_assistant/moveit_setup_framework/CMakeLists.txt @@ -67,7 +67,6 @@ install(FILES moveit_setup_framework_plugins.xml DESTINATION share/moveit_setup_framework) install(DIRECTORY templates DESTINATION share/moveit_setup_framework) -create_deprecated_headers() ament_export_targets(moveit_setup_frameworkTargets HAS_LIBRARY_TARGET) install( diff --git a/moveit_setup_assistant/moveit_setup_simulation/CMakeLists.txt b/moveit_setup_assistant/moveit_setup_simulation/CMakeLists.txt index 8b5ed7a848..127b1e408f 100644 --- a/moveit_setup_assistant/moveit_setup_simulation/CMakeLists.txt +++ b/moveit_setup_assistant/moveit_setup_simulation/CMakeLists.txt @@ -40,7 +40,6 @@ install( install(FILES moveit_setup_framework_plugins.xml DESTINATION share/moveit_setup_simulation) install(DIRECTORY include/ DESTINATION include/moveit_setup_simulation) -create_deprecated_headers() ament_export_targets(moveit_setup_simulationTargets HAS_LIBRARY_TARGET) pluginlib_export_plugin_description_file(moveit_setup_framework diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/CMakeLists.txt b/moveit_setup_assistant/moveit_setup_srdf_plugins/CMakeLists.txt index cf93312033..6e34b6346b 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/CMakeLists.txt +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/CMakeLists.txt @@ -70,7 +70,6 @@ install( install(FILES moveit_setup_framework_plugins.xml DESTINATION share/moveit_setup_srdf_plugins) install(DIRECTORY include/ DESTINATION include/moveit_setup_srdf_plugins) -create_deprecated_headers() ament_export_targets(moveit_setup_srdf_pluginsTargets HAS_LIBRARY_TARGET) pluginlib_export_plugin_description_file(moveit_setup_framework From cdd0b636e9b3408394b6dc52104dfae1c05d03d6 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Thu, 21 Nov 2024 11:34:40 +0000 Subject: [PATCH 33/53] Adds authorship and TODOs --- moveit_common/cmake/deprecated_headers.cmake | 2 ++ moveit_common/scripts/create_deprecated_headers.py | 6 +++++- 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/moveit_common/cmake/deprecated_headers.cmake b/moveit_common/cmake/deprecated_headers.cmake index 6d0622b844..82de954135 100644 --- a/moveit_common/cmake/deprecated_headers.cmake +++ b/moveit_common/cmake/deprecated_headers.cmake @@ -25,6 +25,8 @@ # 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. +# Author: Tom Noble + find_package(PythonInterp REQUIRED) find_package(Python REQUIRED) diff --git a/moveit_common/scripts/create_deprecated_headers.py b/moveit_common/scripts/create_deprecated_headers.py index a119b2631a..432430c9ac 100755 --- a/moveit_common/scripts/create_deprecated_headers.py +++ b/moveit_common/scripts/create_deprecated_headers.py @@ -29,12 +29,16 @@ # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. +# Author: Tom Noble + import sys from pathlib import Path +# TODO: Scan .hpp to include BSD-3 and Author? + ALL_HPPS = "**/*.hpp" USAGE = "Usage: ./generate_deprecated_headers " -DEPRECATION = "{0}.h imports are deprecated. Consider using {0}.hpp" +DEPRECATION = "This header is obsolete. Please use the corresponding .hpp" def create_c_header(include_directory: Path, hpp_path: Path) -> None: From bdf8e7b2e74f413c2a2fd83004e36fb37bc3e22c Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Thu, 21 Nov 2024 16:12:26 +0000 Subject: [PATCH 34/53] Adds new header generator --- moveit/scripts/create_deprecated_headers.py | 99 +++++++++++++++++ moveit/scripts/replace_foo_h.py | 100 ++++++++++++++++++ moveit_common/CMakeLists.txt | 1 - moveit_common/cmake/deprecated_headers.cmake | 43 -------- .../scripts/create_deprecated_headers.py | 58 ---------- 5 files changed, 199 insertions(+), 102 deletions(-) create mode 100755 moveit/scripts/create_deprecated_headers.py create mode 100755 moveit/scripts/replace_foo_h.py delete mode 100644 moveit_common/cmake/deprecated_headers.cmake delete mode 100755 moveit_common/scripts/create_deprecated_headers.py diff --git a/moveit/scripts/create_deprecated_headers.py b/moveit/scripts/create_deprecated_headers.py new file mode 100755 index 0000000000..3eefeb9817 --- /dev/null +++ b/moveit/scripts/create_deprecated_headers.py @@ -0,0 +1,99 @@ +#!/usr/bin/env python3 +# -*- coding: utf-8 -*- + +# Copyright 2021 PickNik Inc. +# +# 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 the PickNik Inc. 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 HOLDER 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. + +# Author: Tom Noble + +import sys +from typing import Type +from pathlib import Path + + +class NoIncludeGuard(Exception): + ERROR = "No include guard found in {}.hpp. Unable to generate pretext." + def __init__(self, file: Path): + super().__init__(self.ERROR.format(file)) + + +class NoIncludeDirectory(Exception): + ERROR = "No includue directory found for {}.hpp. Unable to generate relative .hpp include" + def __init__(self, file: Path): + super().__init__(self.ERROR.format(file)) + + +class HppFile: + + def __init__(self, path: Path): + self.path = path + self.guard = "#pragma once" + + def drop_data_after(self, data: str, match: str): + return data[:data.find(match) + len(match)] + + def read(self) -> str: + data = open(self.path, "r").read() + contains_guard = self.guard in data + if not contains_guard: raise NoIncludeGuard(path) + return data + + def pretext(self) -> str: + data = self.read() + return self.drop_data_after(data, self.guard) + + def include(self) -> str: + ends_with_include = lambda p: str(p).endswith("include") + include_paths = [p for p in self.path.parents if ends_with_include(p)] + if not include_paths: raise NoIncludeDirectory(self.path) + relative_import = self.path.relative_to(include_paths[0]) + return f"#include <{relative_import}>" + + +class DeprecatedHeader: + + def __init__(self, hpp: HppFile): + self.hpp = hpp + self.path = hpp.path.with_suffix(".h") + self.prefix = f"This file was autogenerated by {__file__}" + self.warn = "#pragma message(\".h header is obsolete. Please use the .hpp\")" + self.contents = self.contents() + + def contents(self) -> str: + items = [self.prefix, self.hpp.pretext(), self.warn, self.hpp.include()] + return "\n\n".join(items) + + +USAGE = "Usage: ./create_deprecated_headers [--apply]" + +if __name__ == "__main__": + n_args = len(sys.argv) + if (n_args > 2): sys.exit(USAGE) + apply = "--apply" == sys.argv[1] if n_args == 2 else False + hpps = [HppFile(p) for p in Path.cwd().rglob("*.hpp")] + deprecated_headers = [DeprecatedHeader(hpp) for hpp in hpps] diff --git a/moveit/scripts/replace_foo_h.py b/moveit/scripts/replace_foo_h.py new file mode 100755 index 0000000000..61bee8717c --- /dev/null +++ b/moveit/scripts/replace_foo_h.py @@ -0,0 +1,100 @@ +#!/usr/bin/env python3 +# -*- coding: utf-8 -*- + +# Copyright 2021 PickNik Inc. +# +# 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 the PickNik Inc. 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 HOLDER 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. + +# Author: Tom Noble + +import sys +from typing import Type +from pathlib import Path + + +class NoIncludeGuard(Exception): + ERROR = "No include guard found in {}.hpp. Unable to generate pretext." + def __init__(self, file: Path): + super().__init__(self.ERROR.format(file)) + + +class NoIncludeDirectory(Exception): + ERROR = "No includue directory found for {}.hpp. Unable to generate relative .hpp include" + def __init__(self, file: Path): + super().__init__(self.ERROR.format(file)) + + +class HppFile: + + def __init__(self, path: Path): + self.path = path + self.guard = "#pragma once" + + def drop_data_after(self, data: str, match: str): + return data[:data.find(match) + len(match)] + + def read(self) -> str: + data = open(self.path, "r").read() + contains_guard = self.guard in data + if not contains_guard: raise NoIncludeGuard(path) + return data + + def pretext(self) -> str: + data = self.read() + return self.drop_data_after(data, self.guard) + + def include(self) -> str: + ends_with_include = lambda p: str(p).endswith("include") + include_paths = [p for p in self.path.parents if ends_with_include(p)] + if not include_paths: raise NoIncludeDirectory(self.path) + relative_import = self.path.relative_to(include_paths[0]) + return f"#include <{relative_import}>" + + +class DeprecatedHeader: + + def __init__(self, hpp: HppFile): + self.hpp = hpp + self.path = hpp.path.with_suffix(".h") + self.prefix = f"This file was autogenerated by {__file__}" + self.warn = "#pragma message(\".h header is obsolete. Please use the .hpp\")" + self.contents = self.contents() + + def contents(self) -> str: + items = [self.prefix, self.hpp.pretext(), self.warn, self.hpp.include()] + return "\n\n".join(items) + + +USAGE = "Usage: ./create_deprecated_headers [--apply]" + +if __name__ == "__main__": + n_args = len(sys.argv) + if (n_args > 2): sys.exit(USAGE) + apply = "--apply" == sys.argv[1] if n_args == 2 else False + hpps = [HppFile(p) for p in Path.cwd().rglob("*.hpp")] + deprecated_headers = [DeprecatedHeader(hpp) for hpp in hpps] + diff --git a/moveit_common/CMakeLists.txt b/moveit_common/CMakeLists.txt index 360c8e76d6..c263c6d363 100644 --- a/moveit_common/CMakeLists.txt +++ b/moveit_common/CMakeLists.txt @@ -6,4 +6,3 @@ find_package(ament_cmake REQUIRED) ament_package(CONFIG_EXTRAS "moveit_common-extras.cmake") install(DIRECTORY cmake DESTINATION share/moveit_common) -install(DIRECTORY scripts DESTINATION share/moveit_common) diff --git a/moveit_common/cmake/deprecated_headers.cmake b/moveit_common/cmake/deprecated_headers.cmake deleted file mode 100644 index 82de954135..0000000000 --- a/moveit_common/cmake/deprecated_headers.cmake +++ /dev/null @@ -1,43 +0,0 @@ -# Copyright 2021 PickNik Inc. -# -# 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 the PickNik Inc. 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 HOLDER 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. - -# Author: Tom Noble - -find_package(PythonInterp REQUIRED) -find_package(Python REQUIRED) - -set(SCRIPT ${CMAKE_CURRENT_LIST_DIR}/../scripts/create_deprecated_headers.py) - -# Run to generate deprecated c headers for every .hpp in the local install space -# Note: This is currently unused. See: -# https://github.com/moveit/moveit2/pull/3113 -macro(CREATE_DEPRECATED_HEADERS) - add_custom_target( - ${PROJECT_NAME}_deprecated_headers ALL - COMMAND ${PYTHON_EXECUTABLE} ${SCRIPT} ${CMAKE_INSTALL_PREFIX} - COMMENT "Autogenerating deprecated .h files for ${PROJECT_NAME}") -endmacro() diff --git a/moveit_common/scripts/create_deprecated_headers.py b/moveit_common/scripts/create_deprecated_headers.py deleted file mode 100755 index 432430c9ac..0000000000 --- a/moveit_common/scripts/create_deprecated_headers.py +++ /dev/null @@ -1,58 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- - -# Copyright 2021 PickNik Inc. -# -# 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 the PickNik Inc. 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 HOLDER 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. - -# Author: Tom Noble - -import sys -from pathlib import Path - -# TODO: Scan .hpp to include BSD-3 and Author? - -ALL_HPPS = "**/*.hpp" -USAGE = "Usage: ./generate_deprecated_headers " -DEPRECATION = "This header is obsolete. Please use the corresponding .hpp" - - -def create_c_header(include_directory: Path, hpp_path: Path) -> None: - file = hpp_path.name.replace(".hpp", "") - hpp_import = f"<{hpp_path.relative_to(include_directory)}>" - with open(hpp_path.with_suffix(".h"), "w") as h_file: - h_file.write(f"#warning {DEPRECATION.format(file)}\n") - h_file.write(f"#include {hpp_import}\n") - - -if __name__ == "__main__": - if len(sys.argv) != 2: - sys.exit(USAGE) - include_directory = Path(sys.argv[1]) / "include" - print(str(include_directory)) - for hpp_path in Path(include_directory).rglob(ALL_HPPS): - create_c_header(include_directory, hpp_path) From b0d563f01d4a1c0a61865a7a65a5e4d278537ad0 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Thu, 21 Nov 2024 16:13:04 +0000 Subject: [PATCH 35/53] Removes test script --- moveit/scripts/replace_foo_h.py | 100 -------------------------------- 1 file changed, 100 deletions(-) delete mode 100755 moveit/scripts/replace_foo_h.py diff --git a/moveit/scripts/replace_foo_h.py b/moveit/scripts/replace_foo_h.py deleted file mode 100755 index 61bee8717c..0000000000 --- a/moveit/scripts/replace_foo_h.py +++ /dev/null @@ -1,100 +0,0 @@ -#!/usr/bin/env python3 -# -*- coding: utf-8 -*- - -# Copyright 2021 PickNik Inc. -# -# 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 the PickNik Inc. 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 HOLDER 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. - -# Author: Tom Noble - -import sys -from typing import Type -from pathlib import Path - - -class NoIncludeGuard(Exception): - ERROR = "No include guard found in {}.hpp. Unable to generate pretext." - def __init__(self, file: Path): - super().__init__(self.ERROR.format(file)) - - -class NoIncludeDirectory(Exception): - ERROR = "No includue directory found for {}.hpp. Unable to generate relative .hpp include" - def __init__(self, file: Path): - super().__init__(self.ERROR.format(file)) - - -class HppFile: - - def __init__(self, path: Path): - self.path = path - self.guard = "#pragma once" - - def drop_data_after(self, data: str, match: str): - return data[:data.find(match) + len(match)] - - def read(self) -> str: - data = open(self.path, "r").read() - contains_guard = self.guard in data - if not contains_guard: raise NoIncludeGuard(path) - return data - - def pretext(self) -> str: - data = self.read() - return self.drop_data_after(data, self.guard) - - def include(self) -> str: - ends_with_include = lambda p: str(p).endswith("include") - include_paths = [p for p in self.path.parents if ends_with_include(p)] - if not include_paths: raise NoIncludeDirectory(self.path) - relative_import = self.path.relative_to(include_paths[0]) - return f"#include <{relative_import}>" - - -class DeprecatedHeader: - - def __init__(self, hpp: HppFile): - self.hpp = hpp - self.path = hpp.path.with_suffix(".h") - self.prefix = f"This file was autogenerated by {__file__}" - self.warn = "#pragma message(\".h header is obsolete. Please use the .hpp\")" - self.contents = self.contents() - - def contents(self) -> str: - items = [self.prefix, self.hpp.pretext(), self.warn, self.hpp.include()] - return "\n\n".join(items) - - -USAGE = "Usage: ./create_deprecated_headers [--apply]" - -if __name__ == "__main__": - n_args = len(sys.argv) - if (n_args > 2): sys.exit(USAGE) - apply = "--apply" == sys.argv[1] if n_args == 2 else False - hpps = [HppFile(p) for p in Path.cwd().rglob("*.hpp")] - deprecated_headers = [DeprecatedHeader(hpp) for hpp in hpps] - From a7465de3ef25f5b8ff22b3161a1c134571c7297a Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Thu, 21 Nov 2024 17:15:28 +0000 Subject: [PATCH 36/53] Updates deprecated headers script --- moveit/scripts/create_deprecated_headers.py | 60 +++++++++++++++------ 1 file changed, 45 insertions(+), 15 deletions(-) diff --git a/moveit/scripts/create_deprecated_headers.py b/moveit/scripts/create_deprecated_headers.py index 3eefeb9817..0410feb8cb 100755 --- a/moveit/scripts/create_deprecated_headers.py +++ b/moveit/scripts/create_deprecated_headers.py @@ -32,35 +32,40 @@ # Author: Tom Noble import sys -from typing import Type +import logging +from typing import List, Tuple from pathlib import Path class NoIncludeGuard(Exception): ERROR = "No include guard found in {}.hpp. Unable to generate pretext." + def __init__(self, file: Path): super().__init__(self.ERROR.format(file)) class NoIncludeDirectory(Exception): ERROR = "No includue directory found for {}.hpp. Unable to generate relative .hpp include" + def __init__(self, file: Path): super().__init__(self.ERROR.format(file)) class HppFile: - def __init__(self, path: Path): self.path = path self.guard = "#pragma once" + self.pretext = self.pretext() + self.include = self.include() def drop_data_after(self, data: str, match: str): - return data[:data.find(match) + len(match)] - + return data[: data.find(match) + len(match)] + def read(self) -> str: data = open(self.path, "r").read() contains_guard = self.guard in data - if not contains_guard: raise NoIncludeGuard(path) + if not contains_guard: + raise NoIncludeGuard(self.path) return data def pretext(self) -> str: @@ -70,30 +75,55 @@ def pretext(self) -> str: def include(self) -> str: ends_with_include = lambda p: str(p).endswith("include") include_paths = [p for p in self.path.parents if ends_with_include(p)] - if not include_paths: raise NoIncludeDirectory(self.path) + if not include_paths: + raise NoIncludeDirectory(self.path) relative_import = self.path.relative_to(include_paths[0]) return f"#include <{relative_import}>" class DeprecatedHeader: - def __init__(self, hpp: HppFile): self.hpp = hpp self.path = hpp.path.with_suffix(".h") self.prefix = f"This file was autogenerated by {__file__}" - self.warn = "#pragma message(\".h header is obsolete. Please use the .hpp\")" + self.warn = '#pragma message(".h header is obsolete. Please use the .hpp")' self.contents = self.contents() def contents(self) -> str: - items = [self.prefix, self.hpp.pretext(), self.warn, self.hpp.include()] + items = [self.prefix, self.hpp.pretext, self.warn, self.hpp.include] return "\n\n".join(items) -USAGE = "Usage: ./create_deprecated_headers [--apply]" +def parse_args(args: List) -> bool: + n_args = len(sys.argv) + if n_args > 2: + sys.exit("Usage: ./create_deprecated_headers [--apply]") + apply = "--apply" == sys.argv[1] if n_args == 2 else False + return apply + if __name__ == "__main__": - n_args = len(sys.argv) - if (n_args > 2): sys.exit(USAGE) - apply = "--apply" == sys.argv[1] if n_args == 2 else False - hpps = [HppFile(p) for p in Path.cwd().rglob("*.hpp")] - deprecated_headers = [DeprecatedHeader(hpp) for hpp in hpps] + apply = parse_args(sys.argv) + hpp_paths = list(Path.cwd().rglob("*.hpp")) + print(f"Generating deprecated .h files for {len(hpp_paths)} .hpp files...") + processed = [] + bad = [] + for hpp_path in hpp_paths: + try: + processed.append(HppFile(hpp_path)) + except NoIncludeDirectory as e: + bad.append(str(hpp_path)) + except NoIncludeGuard as e: + bad.append(str(hpp_path)) + print(f"Summary: Can generate {len(processed)} .h files") + if bad: + print(f"Cannot generate .h files for the following files:") + print("\n".join(bad)) + if apply and bad: + answer = input("Proceed to generate? (y/n): ") + apply = answer.lower() == "y" + if apply: + printf("Proceeding to generate {} .h files...") + to_generate = [DeprecatedHeader(hpp) for hpp in processed] + _ = [open(h.path, "r").write(h.contents) for h in to_generate] + printf("Done.") From 4b3304cf97e6bd5ac10205dd21cbcc6fba43e81d Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Thu, 21 Nov 2024 17:22:30 +0000 Subject: [PATCH 37/53] Adds #pragma once to files that don't have it --- .../moveit/collision_detection/test_collision_common_panda.hpp | 2 ++ .../moveit/collision_detection/test_collision_common_pr2.hpp | 2 ++ moveit_core/utils/include/moveit/utils/eigen_test_utils.hpp | 2 ++ .../cached_ik_kinematics_plugin-inl.hpp | 2 ++ .../include/moveit/ompl_interface/detail/goal_union.hpp | 2 ++ .../pilz_industrial_motion_planner/planning_context_lin.hpp | 2 ++ .../moveit_core/collision_detection/collision_common.hpp | 2 ++ .../moveit_core/collision_detection/collision_matrix.hpp | 2 ++ moveit_py/src/moveit/moveit_core/collision_detection/world.hpp | 2 ++ .../src/moveit/moveit_core/kinematic_constraints/utils.hpp | 2 ++ .../planner_logic_plugins/replan_invalidated_trajectory.hpp | 2 ++ .../moveit/planner_logic_plugins/single_plan_execution.hpp | 2 ++ .../moveit/trajectory_operator_plugins/simple_sampler.hpp | 2 ++ moveit_ros/moveit_servo/tests/servo_cpp_fixture.hpp | 2 ++ moveit_ros/moveit_servo/tests/servo_ros_fixture.hpp | 2 ++ moveit_ros/tests/include/parameter_name_list.hpp | 3 +++ 16 files changed, 33 insertions(+) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.hpp b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.hpp index 37fda1c204..4d7b1e095b 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.hpp +++ b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.hpp @@ -34,6 +34,8 @@ /* Author: Jens Petit */ +#pragma once + #include #include #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.hpp b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.hpp index ec5aabb0da..0a652d0b78 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.hpp +++ b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.hpp @@ -34,6 +34,8 @@ /* Author: E. Gil Jones */ +#pragma once + #include #include #include diff --git a/moveit_core/utils/include/moveit/utils/eigen_test_utils.hpp b/moveit_core/utils/include/moveit/utils/eigen_test_utils.hpp index 749ed17d2d..f773db1226 100644 --- a/moveit_core/utils/include/moveit/utils/eigen_test_utils.hpp +++ b/moveit_core/utils/include/moveit/utils/eigen_test_utils.hpp @@ -34,6 +34,8 @@ /* Author: Robert Haschke */ +#pragma once + #include #include #include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.hpp b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.hpp index affcf771ce..5d79f23f71 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.hpp +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.hpp @@ -34,6 +34,8 @@ /* Author: Mark Moll */ +#pragma once + #include #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.hpp b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.hpp index 62f1529c35..9e9592afd3 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.hpp +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.hpp @@ -34,6 +34,8 @@ /* Author: Ioan Sucan */ +#pragma once + #include namespace ompl_interface diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.hpp b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.hpp index dcd3e1724d..865febf5c6 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.hpp +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.hpp @@ -32,6 +32,8 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ +#pragma once + #include #include diff --git a/moveit_py/src/moveit/moveit_core/collision_detection/collision_common.hpp b/moveit_py/src/moveit/moveit_core/collision_detection/collision_common.hpp index eab1c1113e..39d28cc71d 100644 --- a/moveit_py/src/moveit/moveit_core/collision_detection/collision_common.hpp +++ b/moveit_py/src/moveit/moveit_core/collision_detection/collision_common.hpp @@ -34,6 +34,8 @@ /* Author: Peter David Fagan */ +#pragma once + #include #include #include diff --git a/moveit_py/src/moveit/moveit_core/collision_detection/collision_matrix.hpp b/moveit_py/src/moveit/moveit_core/collision_detection/collision_matrix.hpp index f5bbecd912..f01700f197 100644 --- a/moveit_py/src/moveit/moveit_core/collision_detection/collision_matrix.hpp +++ b/moveit_py/src/moveit/moveit_core/collision_detection/collision_matrix.hpp @@ -34,6 +34,8 @@ /* Author: Peter David Fagan */ +#pragma once + #include #include #include diff --git a/moveit_py/src/moveit/moveit_core/collision_detection/world.hpp b/moveit_py/src/moveit/moveit_core/collision_detection/world.hpp index 544ac530cc..4eef37ef47 100644 --- a/moveit_py/src/moveit/moveit_core/collision_detection/world.hpp +++ b/moveit_py/src/moveit/moveit_core/collision_detection/world.hpp @@ -34,6 +34,8 @@ /* Author: Jafar Uruç */ +#pragma once + #include #include #include diff --git a/moveit_py/src/moveit/moveit_core/kinematic_constraints/utils.hpp b/moveit_py/src/moveit/moveit_core/kinematic_constraints/utils.hpp index 355a80e978..b60e619288 100644 --- a/moveit_py/src/moveit/moveit_core/kinematic_constraints/utils.hpp +++ b/moveit_py/src/moveit/moveit_core/kinematic_constraints/utils.hpp @@ -34,6 +34,8 @@ /* Author: Peter David Fagan */ +#pragma once + #include #include #include diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.hpp b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.hpp index 7c70fbc9f5..cffb19c8ee 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.hpp +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.hpp @@ -38,6 +38,8 @@ invalidated global trajectory. */ +#pragma once + #include namespace moveit::hybrid_planning diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.hpp b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.hpp index 795a4543cb..b9671e6160 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.hpp +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.hpp @@ -37,6 +37,8 @@ with the local planner. */ +#pragma once + #include #include diff --git a/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.hpp b/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.hpp index 16a1cd440e..4581a62ce9 100644 --- a/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.hpp +++ b/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.hpp @@ -38,6 +38,8 @@ is updated to the next global trajectory waypoint. Global trajectory updates simply replace the reference trajectory. */ +#pragma once + #include #include diff --git a/moveit_ros/moveit_servo/tests/servo_cpp_fixture.hpp b/moveit_ros/moveit_servo/tests/servo_cpp_fixture.hpp index b8a318a9b6..660efe3d7d 100644 --- a/moveit_ros/moveit_servo/tests/servo_cpp_fixture.hpp +++ b/moveit_ros/moveit_servo/tests/servo_cpp_fixture.hpp @@ -40,6 +40,8 @@ * Description : Resources used by servo c++ integration tests */ +#pragma once + #include #include #include diff --git a/moveit_ros/moveit_servo/tests/servo_ros_fixture.hpp b/moveit_ros/moveit_servo/tests/servo_ros_fixture.hpp index 26f78362cc..2e0662bb1f 100644 --- a/moveit_ros/moveit_servo/tests/servo_ros_fixture.hpp +++ b/moveit_ros/moveit_servo/tests/servo_ros_fixture.hpp @@ -39,6 +39,8 @@ Created : 07/23/2023 */ +#pragma once + #include #include #include diff --git a/moveit_ros/tests/include/parameter_name_list.hpp b/moveit_ros/tests/include/parameter_name_list.hpp index 90c1806fc7..913a482b62 100644 --- a/moveit_ros/tests/include/parameter_name_list.hpp +++ b/moveit_ros/tests/include/parameter_name_list.hpp @@ -36,6 +36,9 @@ /* Author: Sebastian Jahr Description: List of all parameter names used when move_group with OMPL, CHOMP, STOMP and PILZ is launched (01/2024). */ + +#pragma once + #include namespace move_group_test From 16eeb75952b11bee24f22c0d0be487eda5f35ccd Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Thu, 21 Nov 2024 17:48:31 +0000 Subject: [PATCH 38/53] Generate headers where we can --- moveit/scripts/create_deprecated_headers.py | 6 +- .../collision_detector_allocator_allvalid.h | 43 ++++++++++ .../allvalid/collision_env_allvalid.h | 43 ++++++++++ .../collision_detection/collision_common.h | 43 ++++++++++ .../collision_detector_allocator.h | 43 ++++++++++ .../collision_detection/collision_env.h | 43 ++++++++++ .../collision_detection/collision_matrix.h | 43 ++++++++++ .../collision_octomap_filter.h | 43 ++++++++++ .../collision_detection/collision_plugin.h | 41 ++++++++++ .../collision_plugin_cache.h | 41 ++++++++++ .../collision_detection/collision_tools.h | 43 ++++++++++ .../collision_detection/occupancy_map.h | 43 ++++++++++ .../test_collision_common_panda.h | 43 ++++++++++ .../test_collision_common_pr2.h | 43 ++++++++++ .../moveit/collision_detection/world.h | 43 ++++++++++ .../moveit/collision_detection/world_diff.h | 43 ++++++++++ .../bullet_integration/basic_types.h | 27 +++++++ .../bullet_integration/bullet_bvh_manager.h | 40 ++++++++++ .../bullet_cast_bvh_manager.h | 40 ++++++++++ .../bullet_discrete_bvh_manager.h | 40 ++++++++++ .../bullet_integration/bullet_utils.h | 41 ++++++++++ .../contact_checker_common.h | 27 +++++++ .../bullet_integration/ros_bullet_utils.h | 27 +++++++ .../collision_detector_allocator_bullet.h | 43 ++++++++++ .../collision_detector_bullet_plugin_loader.h | 43 ++++++++++ .../collision_env_bullet.h | 43 ++++++++++ .../collision_common.h | 43 ++++++++++ .../collision_detector_allocator_fcl.h | 43 ++++++++++ .../collision_detector_fcl_plugin_loader.h | 43 ++++++++++ .../collision_env_fcl.h | 43 ++++++++++ .../collision_detection_fcl/fcl_compat.h | 43 ++++++++++ .../collision_common_distance_field.h | 43 ++++++++++ ...lision_detector_allocator_distance_field.h | 43 ++++++++++ .../collision_detector_allocator_hybrid.h | 43 ++++++++++ .../collision_distance_field_types.h | 43 ++++++++++ .../collision_env_distance_field.h | 43 ++++++++++ .../collision_env_hybrid.h | 43 ++++++++++ .../constraint_samplers/constraint_sampler.h | 43 ++++++++++ .../constraint_sampler_allocator.h | 43 ++++++++++ .../constraint_sampler_manager.h | 43 ++++++++++ .../constraint_sampler_tools.h | 43 ++++++++++ .../default_constraint_samplers.h | 43 ++++++++++ .../union_constraint_sampler.h | 43 ++++++++++ .../controller_manager/controller_manager.h | 43 ++++++++++ .../moveit/distance_field/distance_field.h | 43 ++++++++++ .../distance_field/find_internal_points.h | 43 ++++++++++ .../propagation_distance_field.h | 43 ++++++++++ .../moveit/distance_field/voxel_grid.h | 43 ++++++++++ .../moveit/dynamics_solver/dynamics_solver.h | 43 ++++++++++ .../include/moveit/exceptions/exceptions.h | 43 ++++++++++ .../kinematic_constraint.h | 43 ++++++++++ .../moveit/kinematic_constraints/utils.h | 43 ++++++++++ .../moveit/kinematics_base/kinematics_base.h | 43 ++++++++++ .../kinematics_metrics/kinematics_metrics.h | 43 ++++++++++ .../include/moveit/macros/class_forward.h | 43 ++++++++++ .../include/moveit/macros/console_colors.h | 43 ++++++++++ .../include/moveit/macros/declare_ptr.h | 41 ++++++++++ .../include/moveit/macros/deprecation.h | 41 ++++++++++ .../acceleration_filter.h | 79 +++++++++++++++++++ .../butterworth_filter.h | 46 +++++++++++ .../online_signal_smoothing/ruckig_filter.h | 45 +++++++++++ .../smoothing_base_class.h | 45 +++++++++++ .../planning_interface/planning_interface.h | 43 ++++++++++ .../planning_interface/planning_request.h | 43 ++++++++++ .../planning_request_adapter.h | 45 +++++++++++ .../planning_interface/planning_response.h | 43 ++++++++++ .../planning_response_adapter.h | 43 ++++++++++ .../moveit/planning_scene/planning_scene.h | 43 ++++++++++ .../include/moveit/robot_model/aabb.h | 43 ++++++++++ .../moveit/robot_model/fixed_joint_model.h | 43 ++++++++++ .../moveit/robot_model/floating_joint_model.h | 43 ++++++++++ .../include/moveit/robot_model/joint_model.h | 44 +++++++++++ .../moveit/robot_model/joint_model_group.h | 44 +++++++++++ .../include/moveit/robot_model/link_model.h | 43 ++++++++++ .../moveit/robot_model/planar_joint_model.h | 43 ++++++++++ .../robot_model/prismatic_joint_model.h | 43 ++++++++++ .../moveit/robot_model/revolute_joint_model.h | 43 ++++++++++ .../include/moveit/robot_model/robot_model.h | 44 +++++++++++ .../moveit/robot_state/attached_body.h | 43 ++++++++++ .../robot_state/cartesian_interpolator.h | 45 +++++++++++ .../include/moveit/robot_state/conversions.h | 43 ++++++++++ .../include/moveit/robot_state/robot_state.h | 44 +++++++++++ .../robot_trajectory/robot_trajectory.h | 43 ++++++++++ .../ruckig_traj_smoothing.h | 42 ++++++++++ .../time_optimal_trajectory_generation.h | 45 +++++++++++ .../time_parameterization.h | 7 ++ .../trajectory_processing/trajectory_tools.h | 43 ++++++++++ .../include/moveit/transforms/transforms.h | 43 ++++++++++ .../include/moveit/utils/eigen_test_utils.h | 43 ++++++++++ .../include/moveit/utils/lexical_casts.h | 43 ++++++++++ .../utils/include/moveit/utils/logger.h | 43 ++++++++++ .../include/moveit/utils/message_checks.h | 43 ++++++++++ .../include/moveit/utils/moveit_error_code.h | 41 ++++++++++ .../utils/include/moveit/utils/rclcpp_utils.h | 34 ++++++++ .../moveit/utils/robot_model_test_utils.h | 44 +++++++++++ .../cached_ik_kinematics_plugin-inl.h | 43 ++++++++++ .../cached_ik_kinematics_plugin.h | 43 ++++++++++ .../detail/GreedyKCenters.h | 45 +++++++++++ .../detail/NearestNeighbors.h | 45 +++++++++++ .../detail/NearestNeighborsGNAT.h | 45 +++++++++++ .../chainiksolver_vel_mimic_svd.h | 32 ++++++++ .../kdl_kinematics_plugin/joint_mimic.h | 43 ++++++++++ .../kdl_kinematics_plugin.h | 43 ++++++++++ .../srv_kinematics_plugin.h | 48 +++++++++++ .../include/chomp_interface/chomp_interface.h | 43 ++++++++++ .../chomp_interface/chomp_planning_context.h | 43 ++++++++++ .../include/chomp_motion_planner/chomp_cost.h | 43 ++++++++++ .../chomp_motion_planner/chomp_optimizer.h | 43 ++++++++++ .../chomp_motion_planner/chomp_parameters.h | 46 +++++++++++ .../chomp_motion_planner/chomp_planner.h | 43 ++++++++++ .../chomp_motion_planner/chomp_trajectory.h | 43 ++++++++++ .../chomp_motion_planner/chomp_utils.h | 43 ++++++++++ .../multivariate_gaussian.h | 43 ++++++++++ .../detail/constrained_goal_sampler.h | 43 ++++++++++ .../detail/constrained_sampler.h | 43 ++++++++++ .../detail/constraint_approximations.h | 43 ++++++++++ .../detail/constraints_library.h | 43 ++++++++++ .../moveit/ompl_interface/detail/goal_union.h | 43 ++++++++++ .../ompl_interface/detail/ompl_constraints.h | 43 ++++++++++ .../detail/projection_evaluators.h | 43 ++++++++++ .../detail/state_validity_checker.h | 54 +++++++++++++ .../detail/threadsafe_state_storage.h | 43 ++++++++++ .../model_based_planning_context.h | 43 ++++++++++ .../moveit/ompl_interface/ompl_interface.h | 43 ++++++++++ .../constrained_planning_state_space.h | 43 ++++++++++ ...constrained_planning_state_space_factory.h | 44 +++++++++++ .../joint_space/joint_model_state_space.h | 43 ++++++++++ .../joint_model_state_space_factory.h | 43 ++++++++++ .../model_based_state_space.h | 43 ++++++++++ .../model_based_state_space_factory.h | 43 ++++++++++ .../work_space/pose_model_state_space.h | 43 ++++++++++ .../pose_model_state_space_factory.h | 43 ++++++++++ .../ompl_interface/planning_context_manager.h | 43 ++++++++++ .../include/joint_limits_copy/joint_limits.h | 23 ++++++ .../joint_limits_copy/joint_limits_rosparam.h | 23 ++++++ .../capability_names.h | 41 ++++++++++ .../cartesian_trajectory.h | 41 ++++++++++ .../cartesian_trajectory_point.h | 41 ++++++++++ .../command_list_manager.h | 41 ++++++++++ .../joint_limits_aggregator.h | 41 ++++++++++ .../joint_limits_container.h | 41 ++++++++++ .../joint_limits_extension.h | 41 ++++++++++ .../joint_limits_interface_extension.h | 41 ++++++++++ .../joint_limits_validator.h | 41 ++++++++++ .../limits_container.h | 41 ++++++++++ .../move_group_sequence_action.h | 41 ++++++++++ .../move_group_sequence_service.h | 41 ++++++++++ .../path_circle_generator.h | 41 ++++++++++ .../pilz_industrial_motion_planner.h | 41 ++++++++++ .../plan_components_builder.h | 41 ++++++++++ .../planning_context_base.h | 41 ++++++++++ .../planning_context_circ.h | 41 ++++++++++ .../planning_context_lin.h | 41 ++++++++++ .../planning_context_loader.h | 41 ++++++++++ .../planning_context_loader_circ.h | 41 ++++++++++ .../planning_context_loader_lin.h | 41 ++++++++++ .../planning_context_loader_ptp.h | 41 ++++++++++ .../planning_context_ptp.h | 41 ++++++++++ .../planning_exceptions.h | 41 ++++++++++ .../tip_frame_getter.h | 41 ++++++++++ .../trajectory_blend_request.h | 41 ++++++++++ .../trajectory_blend_response.h | 41 ++++++++++ .../trajectory_blender.h | 41 ++++++++++ .../trajectory_blender_transition_window.h | 41 ++++++++++ .../trajectory_functions.h | 41 ++++++++++ .../trajectory_generation_exceptions.h | 41 ++++++++++ .../trajectory_generator.h | 41 ++++++++++ .../trajectory_generator_circ.h | 41 ++++++++++ .../trajectory_generator_lin.h | 41 ++++++++++ .../trajectory_generator_ptp.h | 41 ++++++++++ .../velocity_profile_atrap.h | 41 ++++++++++ .../async_test.h | 23 ++++++ .../basecmd.h | 41 ++++++++++ .../cartesianconfiguration.h | 41 ++++++++++ .../cartesianpathconstraintsbuilder.h | 41 ++++++++++ .../center.h | 41 ++++++++++ .../checks.h | 41 ++++++++++ .../circ.h | 41 ++++++++++ .../circ_auxiliary_types.h | 41 ++++++++++ .../circauxiliary.h | 41 ++++++++++ .../command_types_typedef.h | 41 ++++++++++ .../default_values.h | 41 ++++++++++ .../exception_types.h | 41 ++++++++++ .../goalconstraintsmsgconvertible.h | 41 ++++++++++ .../gripper.h | 41 ++++++++++ .../interim.h | 41 ++++++++++ .../jointconfiguration.h | 41 ++++++++++ .../lin.h | 41 ++++++++++ .../motioncmd.h | 41 ++++++++++ .../motionplanrequestconvertible.h | 41 ++++++++++ .../ptp.h | 41 ++++++++++ .../robotconfiguration.h | 41 ++++++++++ .../robotstatemsgconvertible.h | 41 ++++++++++ .../sequence.h | 41 ++++++++++ .../testdata_loader.h | 41 ++++++++++ .../xml_constants.h | 41 ++++++++++ .../xml_testdata_loader.h | 41 ++++++++++ .../stomp_moveit/conversion_functions.h | 46 +++++++++++ .../include/stomp_moveit/cost_functions.h | 46 +++++++++++ .../include/stomp_moveit/filter_functions.h | 46 +++++++++++ .../stomp_moveit/math/multivariate_gaussian.h | 46 +++++++++++ .../include/stomp_moveit/noise_generators.h | 46 +++++++++++ .../stomp_moveit_planning_context.h | 46 +++++++++++ .../include/stomp_moveit/stomp_moveit_task.h | 61 ++++++++++++++ .../stomp_moveit/trajectory_visualization.h | 46 +++++++++++ .../ControllerHandle.h | 43 ++++++++++ .../action_based_controller_handle.h | 44 +++++++++++ .../empty_controller_handle.h | 43 ++++++++++ ...ollow_joint_trajectory_controller_handle.h | 44 +++++++++++ .../gripper_controller_handle.h | 44 +++++++++++ .../moveit_py/moveit_py_utils/copy_ros_msg.h | 43 ++++++++++ .../moveit_py_utils/ros_msg_typecasters.h | 43 ++++++++++ .../moveit/benchmarks/BenchmarkExecutor.h | 43 ++++++++++ .../moveit/benchmarks/BenchmarkOptions.h | 43 ++++++++++ .../global_planner/global_planner_component.h | 45 +++++++++++ .../global_planner/global_planner_interface.h | 46 +++++++++++ .../global_planner/moveit_planning_pipeline.h | 44 +++++++++++ .../hybrid_planning_events.h | 44 +++++++++++ .../hybrid_planning_manager.h | 45 +++++++++++ .../planner_logic_interface.h | 45 +++++++++++ .../replan_invalidated_trajectory.h | 47 +++++++++++ .../single_plan_execution.h | 46 +++++++++++ .../forward_trajectory.h | 47 +++++++++++ .../moveit/local_planner/feedback_types.h | 46 +++++++++++ .../local_constraint_solver_interface.h | 45 +++++++++++ .../local_planner/local_planner_component.h | 46 +++++++++++ .../trajectory_operator_interface.h | 45 +++++++++++ .../simple_sampler.h | 47 +++++++++++ .../moveit/move_group/capability_names.h | 43 ++++++++++ .../moveit/move_group/move_group_capability.h | 43 ++++++++++ .../moveit/move_group/move_group_context.h | 43 ++++++++++ .../include/moveit_servo/collision_monitor.h | 48 +++++++++++ .../moveit_servo/include/moveit_servo/servo.h | 48 +++++++++++ .../include/moveit_servo/servo_node.h | 48 +++++++++++ .../include/moveit_servo/utils/command.h | 48 +++++++++++ .../include/moveit_servo/utils/common.h | 48 +++++++++++ .../include/moveit_servo/utils/datatypes.h | 48 +++++++++++ .../occupancy_map_monitor.h | 43 ++++++++++ .../occupancy_map_monitor_middleware_handle.h | 43 ++++++++++ .../occupancy_map_updater.h | 43 ++++++++++ .../depth_image_octomap_updater.h | 43 ++++++++++ .../lazy_free_space_updater.h | 43 ++++++++++ .../mesh_filter/depth_self_filter_nodelet.h | 43 ++++++++++ .../include/moveit/mesh_filter/filter_job.h | 43 ++++++++++ .../include/moveit/mesh_filter/gl_mesh.h | 43 ++++++++++ .../include/moveit/mesh_filter/gl_renderer.h | 43 ++++++++++ .../include/moveit/mesh_filter/mesh_filter.h | 43 ++++++++++ .../moveit/mesh_filter/mesh_filter_base.h | 43 ++++++++++ .../include/moveit/mesh_filter/sensor_model.h | 43 ++++++++++ .../moveit/mesh_filter/stereo_camera_model.h | 43 ++++++++++ .../moveit/mesh_filter/transform_provider.h | 43 ++++++++++ .../point_containment_filter/shape_mask.h | 43 ++++++++++ .../pointcloud_octomap_updater.h | 43 ++++++++++ .../moveit/semantic_world/semantic_world.h | 43 ++++++++++ .../collision_plugin_loader.h | 41 ++++++++++ .../constraint_sampler_manager_loader.h | 43 ++++++++++ .../kinematics_plugin_loader.h | 43 ++++++++++ .../include/moveit/moveit_cpp/moveit_cpp.h | 46 +++++++++++ .../moveit/moveit_cpp/planning_component.h | 44 +++++++++++ .../moveit/plan_execution/plan_execution.h | 43 ++++++++++ .../plan_execution/plan_representation.h | 43 ++++++++++ .../planning_pipeline/planning_pipeline.h | 46 +++++++++++ .../plan_responses_container.h | 44 +++++++++++ .../planning_pipeline_interfaces.h | 44 +++++++++++ .../solution_selection_functions.h | 44 +++++++++++ .../stopping_criterion_functions.h | 44 +++++++++++ .../current_state_monitor.h | 43 ++++++++++ .../current_state_monitor_middleware_handle.h | 43 ++++++++++ .../planning_scene_monitor.h | 43 ++++++++++ .../trajectory_monitor.h | 43 ++++++++++ .../trajectory_monitor_middleware_handle.h | 43 ++++++++++ .../include/moveit/rdf_loader/rdf_loader.h | 43 ++++++++++ .../synchronized_string_parameter.h | 43 ++++++++++ .../robot_model_loader/robot_model_loader.h | 43 ++++++++++ .../trajectory_execution_manager.h | 43 ++++++++++ .../common_objects.h | 43 ++++++++++ .../move_group_interface.h | 44 +++++++++++ .../planning_scene_interface.h | 43 ++++++++++ .../moveit/robot_interaction/interaction.h | 43 ++++++++++ .../robot_interaction/interaction_handler.h | 43 ++++++++++ .../interactive_marker_helpers.h | 43 ++++++++++ .../robot_interaction/kinematic_options.h | 43 ++++++++++ .../robot_interaction/kinematic_options_map.h | 43 ++++++++++ .../robot_interaction/locked_robot_state.h | 44 +++++++++++ .../robot_interaction/robot_interaction.h | 43 ++++++++++ .../tests/include/parameter_name_list.h | 46 +++++++++++ .../trajectory_cache/trajectory_cache.h | 26 ++++++ .../interactive_marker_display.h | 42 ++++++++++ .../motion_planning_display.h | 43 ++++++++++ .../motion_planning_frame.h | 43 ++++++++++ .../motion_planning_frame_joints_widget.h | 43 ++++++++++ .../motion_planning_param_widget.h | 43 ++++++++++ .../background_processing.h | 43 ++++++++++ .../planning_scene_display.h | 43 ++++++++++ .../robot_state_display.h | 43 ++++++++++ .../rviz_plugin_render_tools/octomap_render.h | 43 ++++++++++ .../planning_link_updater.h | 43 ++++++++++ .../planning_scene_render.h | 43 ++++++++++ .../rviz_plugin_render_tools/render_shapes.h | 43 ++++++++++ .../robot_state_visualization.h | 43 ++++++++++ .../trajectory_panel.h | 43 ++++++++++ .../trajectory_visualization.h | 43 ++++++++++ .../include/ogre_helpers/mesh_shape.h | 36 +++++++++ .../trajectory_display.h | 45 +++++++++++ .../moveit/warehouse/constraints_storage.h | 43 ++++++++++ .../moveit/warehouse/moveit_message_storage.h | 43 ++++++++++ .../moveit/warehouse/planning_scene_storage.h | 43 ++++++++++ .../warehouse/planning_scene_world_storage.h | 43 ++++++++++ .../include/moveit/warehouse/state_storage.h | 43 ++++++++++ .../trajectory_constraints_storage.h | 43 ++++++++++ .../moveit/warehouse/warehouse_connector.h | 43 ++++++++++ .../moveit_setup_app_plugins/launch_bundle.h | 42 ++++++++++ .../moveit_setup_app_plugins/launches.h | 42 ++++++++++ .../launches_config.h | 42 ++++++++++ .../launches_widget.h | 42 ++++++++++ .../moveit_setup_app_plugins/perception.h | 42 ++++++++++ .../perception_config.h | 42 ++++++++++ .../perception_widget.h | 42 ++++++++++ .../navigation_widget.h | 43 ++++++++++ .../setup_assistant_widget.h | 43 ++++++++++ .../control_xacro_config.h | 43 ++++++++++ .../controller_edit_widget.h | 42 ++++++++++ .../moveit_setup_controllers/controllers.h | 42 ++++++++++ .../controllers_config.h | 42 ++++++++++ .../controllers_widget.h | 42 ++++++++++ .../included_xacro_config.h | 43 ++++++++++ .../modified_urdf_config.h | 43 ++++++++++ .../moveit_controllers.h | 43 ++++++++++ .../moveit_controllers_config.h | 43 ++++++++++ .../ros2_controllers.h | 43 ++++++++++ .../ros2_controllers_config.h | 43 ++++++++++ .../urdf_modifications.h | 42 ++++++++++ .../urdf_modifications_widget.h | 43 ++++++++++ .../author_information.h | 42 ++++++++++ .../author_information_widget.h | 43 ++++++++++ .../configuration_files.h | 41 ++++++++++ .../configuration_files_widget.h | 43 ++++++++++ .../moveit_setup_core_plugins/start_screen.h | 41 ++++++++++ .../start_screen_widget.h | 43 ++++++++++ .../include/moveit_setup_framework/config.h | 43 ++++++++++ .../data/package_settings_config.h | 41 ++++++++++ .../moveit_setup_framework/data/srdf_config.h | 42 ++++++++++ .../moveit_setup_framework/data/urdf_config.h | 41 ++++++++++ .../moveit_setup_framework/data_warehouse.h | 49 ++++++++++++ .../moveit_setup_framework/generated_file.h | 43 ++++++++++ .../moveit_setup_framework/generated_time.h | 43 ++++++++++ .../qt/double_list_widget.h | 43 ++++++++++ .../qt/helper_widgets.h | 43 ++++++++++ .../moveit_setup_framework/qt/rviz_panel.h | 43 ++++++++++ .../qt/setup_step_widget.h | 43 ++++++++++ .../qt/xml_syntax_highlighter.h | 43 ++++++++++ .../moveit_setup_framework/setup_step.h | 43 ++++++++++ .../moveit_setup_framework/templates.h | 42 ++++++++++ .../moveit_setup_framework/testing_utils.h | 43 ++++++++++ .../moveit_setup_framework/utilities.h | 43 ++++++++++ .../moveit_setup_simulation/simulation.h | 42 ++++++++++ .../simulation_widget.h | 42 ++++++++++ .../collision_linear_model.h | 43 ++++++++++ .../collision_matrix_model.h | 43 ++++++++++ .../compute_default_collisions.h | 43 ++++++++++ .../default_collisions.h | 42 ++++++++++ .../default_collisions_widget.h | 43 ++++++++++ .../moveit_setup_srdf_plugins/end_effectors.h | 42 ++++++++++ .../end_effectors_widget.h | 43 ++++++++++ .../group_edit_widget.h | 43 ++++++++++ .../group_meta_config.h | 42 ++++++++++ .../kinematic_chain_widget.h | 43 ++++++++++ .../passive_joints.h | 42 ++++++++++ .../passive_joints_widget.h | 43 ++++++++++ .../planning_groups.h | 42 ++++++++++ .../planning_groups_widget.h | 43 ++++++++++ .../moveit_setup_srdf_plugins/robot_poses.h | 42 ++++++++++ .../robot_poses_widget.h | 43 ++++++++++ .../rotated_header_view.h | 43 ++++++++++ .../moveit_setup_srdf_plugins/srdf_step.h | 42 ++++++++++ .../virtual_joints.h | 42 ++++++++++ .../virtual_joints_widget.h | 43 ++++++++++ 377 files changed, 16015 insertions(+), 3 deletions(-) create mode 100644 moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h create mode 100644 moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h create mode 100644 moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h create mode 100644 moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h create mode 100644 moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h create mode 100644 moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h create mode 100644 moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h create mode 100644 moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h create mode 100644 moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h create mode 100644 moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h create mode 100644 moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h create mode 100644 moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h create mode 100644 moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h create mode 100644 moveit_core/collision_detection/include/moveit/collision_detection/world.h create mode 100644 moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h create mode 100644 moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h create mode 100644 moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h create mode 100644 moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h create mode 100644 moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h create mode 100644 moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h create mode 100644 moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h create mode 100644 moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h create mode 100644 moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h create mode 100644 moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h create mode 100644 moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h create mode 100644 moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h create mode 100644 moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h create mode 100644 moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h create mode 100644 moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h create mode 100644 moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h create mode 100644 moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h create mode 100644 moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h create mode 100644 moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h create mode 100644 moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h create mode 100644 moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h create mode 100644 moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h create mode 100644 moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h create mode 100644 moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h create mode 100644 moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h create mode 100644 moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h create mode 100644 moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h create mode 100644 moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h create mode 100644 moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h create mode 100644 moveit_core/distance_field/include/moveit/distance_field/distance_field.h create mode 100644 moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h create mode 100644 moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h create mode 100644 moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h create mode 100644 moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h create mode 100644 moveit_core/exceptions/include/moveit/exceptions/exceptions.h create mode 100644 moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h create mode 100644 moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h create mode 100644 moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h create mode 100644 moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h create mode 100644 moveit_core/macros/include/moveit/macros/class_forward.h create mode 100644 moveit_core/macros/include/moveit/macros/console_colors.h create mode 100644 moveit_core/macros/include/moveit/macros/declare_ptr.h create mode 100644 moveit_core/macros/include/moveit/macros/deprecation.h create mode 100644 moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h create mode 100644 moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h create mode 100644 moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h create mode 100644 moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h create mode 100644 moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h create mode 100644 moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h create mode 100644 moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h create mode 100644 moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h create mode 100644 moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h create mode 100644 moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h create mode 100644 moveit_core/robot_model/include/moveit/robot_model/aabb.h create mode 100644 moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h create mode 100644 moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h create mode 100644 moveit_core/robot_model/include/moveit/robot_model/joint_model.h create mode 100644 moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h create mode 100644 moveit_core/robot_model/include/moveit/robot_model/link_model.h create mode 100644 moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h create mode 100644 moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h create mode 100644 moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h create mode 100644 moveit_core/robot_model/include/moveit/robot_model/robot_model.h create mode 100644 moveit_core/robot_state/include/moveit/robot_state/attached_body.h create mode 100644 moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h create mode 100644 moveit_core/robot_state/include/moveit/robot_state/conversions.h create mode 100644 moveit_core/robot_state/include/moveit/robot_state/robot_state.h create mode 100644 moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h create mode 100644 moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h create mode 100644 moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h create mode 100644 moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h create mode 100644 moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h create mode 100644 moveit_core/transforms/include/moveit/transforms/transforms.h create mode 100644 moveit_core/utils/include/moveit/utils/eigen_test_utils.h create mode 100644 moveit_core/utils/include/moveit/utils/lexical_casts.h create mode 100644 moveit_core/utils/include/moveit/utils/logger.h create mode 100644 moveit_core/utils/include/moveit/utils/message_checks.h create mode 100644 moveit_core/utils/include/moveit/utils/moveit_error_code.h create mode 100644 moveit_core/utils/include/moveit/utils/rclcpp_utils.h create mode 100644 moveit_core/utils/include/moveit/utils/robot_model_test_utils.h create mode 100644 moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h create mode 100644 moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h create mode 100644 moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h create mode 100644 moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h create mode 100644 moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h create mode 100644 moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h create mode 100644 moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h create mode 100644 moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h create mode 100644 moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h create mode 100644 moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h create mode 100644 moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h create mode 100644 moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h create mode 100644 moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h create mode 100644 moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h create mode 100644 moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h create mode 100644 moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h create mode 100644 moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h create mode 100644 moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h create mode 100644 moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h create mode 100644 moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h create mode 100644 moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h create mode 100644 moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h create mode 100644 moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h create mode 100644 moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h create mode 100644 moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h create mode 100644 moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h create mode 100644 moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h create mode 100644 moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h create mode 100644 moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h create mode 100644 moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h create mode 100644 moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h create mode 100644 moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h create mode 100644 moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h create mode 100644 moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h create mode 100644 moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h create mode 100644 moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h create mode 100644 moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h create mode 100644 moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h create mode 100644 moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h create mode 100644 moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h create mode 100644 moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h create mode 100644 moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h create mode 100644 moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h create mode 100644 moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h create mode 100644 moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h create mode 100644 moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h create mode 100644 moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h create mode 100644 moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h create mode 100644 moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h create mode 100644 moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h create mode 100644 moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h create mode 100644 moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h create mode 100644 moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h create mode 100644 moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h create mode 100644 moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h create mode 100644 moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h create mode 100644 moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h create mode 100644 moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h create mode 100644 moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h create mode 100644 moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h create mode 100644 moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h create mode 100644 moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h create mode 100644 moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h create mode 100644 moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h create mode 100644 moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h create mode 100644 moveit_planners/stomp/include/stomp_moveit/conversion_functions.h create mode 100644 moveit_planners/stomp/include/stomp_moveit/cost_functions.h create mode 100644 moveit_planners/stomp/include/stomp_moveit/filter_functions.h create mode 100644 moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h create mode 100644 moveit_planners/stomp/include/stomp_moveit/noise_generators.h create mode 100644 moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h create mode 100644 moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h create mode 100644 moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h create mode 100644 moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h create mode 100644 moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h create mode 100644 moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h create mode 100644 moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h create mode 100644 moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h create mode 100644 moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h create mode 100644 moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h create mode 100644 moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h create mode 100644 moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h create mode 100644 moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h create mode 100644 moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h create mode 100644 moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h create mode 100644 moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h create mode 100644 moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h create mode 100644 moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h create mode 100644 moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h create mode 100644 moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h create mode 100644 moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h create mode 100644 moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h create mode 100644 moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h create mode 100644 moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h create mode 100644 moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h create mode 100644 moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h create mode 100644 moveit_ros/move_group/include/moveit/move_group/capability_names.h create mode 100644 moveit_ros/move_group/include/moveit/move_group/move_group_capability.h create mode 100644 moveit_ros/move_group/include/moveit/move_group/move_group_context.h create mode 100644 moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h create mode 100644 moveit_ros/moveit_servo/include/moveit_servo/servo.h create mode 100644 moveit_ros/moveit_servo/include/moveit_servo/servo_node.h create mode 100644 moveit_ros/moveit_servo/include/moveit_servo/utils/command.h create mode 100644 moveit_ros/moveit_servo/include/moveit_servo/utils/common.h create mode 100644 moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h create mode 100644 moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h create mode 100644 moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h create mode 100644 moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h create mode 100644 moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h create mode 100644 moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h create mode 100644 moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h create mode 100644 moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h create mode 100644 moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h create mode 100644 moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h create mode 100644 moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h create mode 100644 moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h create mode 100644 moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h create mode 100644 moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h create mode 100644 moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h create mode 100644 moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h create mode 100644 moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h create mode 100644 moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h create mode 100644 moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h create mode 100644 moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h create mode 100644 moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h create mode 100644 moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h create mode 100644 moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h create mode 100644 moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h create mode 100644 moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h create mode 100644 moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h create mode 100644 moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h create mode 100644 moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h create mode 100644 moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h create mode 100644 moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h create mode 100644 moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h create mode 100644 moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h create mode 100644 moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h create mode 100644 moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h create mode 100644 moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h create mode 100644 moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h create mode 100644 moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h create mode 100644 moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h create mode 100644 moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h create mode 100644 moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h create mode 100644 moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h create mode 100644 moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h create mode 100644 moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h create mode 100644 moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h create mode 100644 moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h create mode 100644 moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h create mode 100644 moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h create mode 100644 moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h create mode 100644 moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h create mode 100644 moveit_ros/tests/include/parameter_name_list.h create mode 100644 moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h create mode 100644 moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h create mode 100644 moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h create mode 100644 moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h create mode 100644 moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h create mode 100644 moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h create mode 100644 moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h create mode 100644 moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h create mode 100644 moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h create mode 100644 moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h create mode 100644 moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h create mode 100644 moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h create mode 100644 moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h create mode 100644 moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h create mode 100644 moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h create mode 100644 moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h create mode 100644 moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h create mode 100644 moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h create mode 100644 moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h create mode 100644 moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h create mode 100644 moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h create mode 100644 moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h create mode 100644 moveit_ros/warehouse/include/moveit/warehouse/state_storage.h create mode 100644 moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h create mode 100644 moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h create mode 100644 moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h create mode 100644 moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h create mode 100644 moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h create mode 100644 moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h create mode 100644 moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h create mode 100644 moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h create mode 100644 moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h create mode 100644 moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h create mode 100644 moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h create mode 100644 moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h create mode 100644 moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h create mode 100644 moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h create mode 100644 moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h create mode 100644 moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h create mode 100644 moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h create mode 100644 moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h create mode 100644 moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h create mode 100644 moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h create mode 100644 moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h create mode 100644 moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h create mode 100644 moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h create mode 100644 moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h create mode 100644 moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h create mode 100644 moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h create mode 100644 moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h create mode 100644 moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h create mode 100644 moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h create mode 100644 moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h create mode 100644 moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h create mode 100644 moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h create mode 100644 moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h create mode 100644 moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h create mode 100644 moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h create mode 100644 moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h create mode 100644 moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h create mode 100644 moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h create mode 100644 moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h create mode 100644 moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h create mode 100644 moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h create mode 100644 moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h create mode 100644 moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h create mode 100644 moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h create mode 100644 moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h create mode 100644 moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h create mode 100644 moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h create mode 100644 moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h create mode 100644 moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h create mode 100644 moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h create mode 100644 moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h create mode 100644 moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h create mode 100644 moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h create mode 100644 moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h create mode 100644 moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h create mode 100644 moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h create mode 100644 moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h create mode 100644 moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h create mode 100644 moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h create mode 100644 moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h create mode 100644 moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h create mode 100644 moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h create mode 100644 moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h create mode 100644 moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h create mode 100644 moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h create mode 100644 moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h create mode 100644 moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h create mode 100644 moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h diff --git a/moveit/scripts/create_deprecated_headers.py b/moveit/scripts/create_deprecated_headers.py index 0410feb8cb..9a30db1a41 100755 --- a/moveit/scripts/create_deprecated_headers.py +++ b/moveit/scripts/create_deprecated_headers.py @@ -123,7 +123,7 @@ def parse_args(args: List) -> bool: answer = input("Proceed to generate? (y/n): ") apply = answer.lower() == "y" if apply: - printf("Proceeding to generate {} .h files...") + print("Proceeding to generate {} .h files...") to_generate = [DeprecatedHeader(hpp) for hpp in processed] - _ = [open(h.path, "r").write(h.contents) for h in to_generate] - printf("Done.") + _ = [open(h.path, "w").write(h.contents) for h in to_generate] + print("Done.") diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h new file mode 100644 index 0000000000..55a5c952ec --- /dev/null +++ b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Acorn Pooley, Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h new file mode 100644 index 0000000000..a654b1fcd8 --- /dev/null +++ b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan, Jia Pan, Jens Petit */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h new file mode 100644 index 0000000000..917d1ffc33 --- /dev/null +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h new file mode 100644 index 0000000000..1ea509f5ef --- /dev/null +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Acorn Pooley, Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h new file mode 100644 index 0000000000..ccaa7a0266 --- /dev/null +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 the copyright holder 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. + *********************************************************************/ + +/* Author: Ioan Sucan, Jens Petit */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h new file mode 100644 index 0000000000..cafe073768 --- /dev/null +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan, E. Gil Jones */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h new file mode 100644 index 0000000000..3b86b18a8b --- /dev/null +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Adam Leeper */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h new file mode 100644 index 0000000000..d61b489143 --- /dev/null +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2014 Fetch Robotics Inc. + * 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 Fetch Robotics 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h new file mode 100644 index 0000000000..3a58b2cdf8 --- /dev/null +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2014 Fetch Robotics Inc. + * 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 Fetch Robotics 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h new file mode 100644 index 0000000000..ff191d6790 --- /dev/null +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h b/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h new file mode 100644 index 0000000000..fd6c332bf9 --- /dev/null +++ b/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan, Jon Binney */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h new file mode 100644 index 0000000000..ebc6065d1b --- /dev/null +++ b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019, Jens Petit + * 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 the copyright holder 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. + *********************************************************************/ + +/* Author: Jens Petit */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h new file mode 100644 index 0000000000..9003a65db9 --- /dev/null +++ b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: E. Gil Jones */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/world.h b/moveit_core/collision_detection/include/moveit/collision_detection/world.h new file mode 100644 index 0000000000..c4eb520017 --- /dev/null +++ b/moveit_core/collision_detection/include/moveit/collision_detection/world.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan, Acorn Pooley, Sachin Chitta */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h b/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h new file mode 100644 index 0000000000..31c28b2314 --- /dev/null +++ b/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Acorn Pooley, Ioan Sucan, Sachin Chitta */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h new file mode 100644 index 0000000000..6c0c80c472 --- /dev/null +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h @@ -0,0 +1,27 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (Apache License) + * + * Copyright (c) 2013, Southwest Research Institute + * All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *********************************************************************/ + +/* Author: Levi Armstrong */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h new file mode 100644 index 0000000000..5a33c73dce --- /dev/null +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h @@ -0,0 +1,40 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD-2-Clause) + * + * Copyright (c) 2017, Southwest Research Institute + * 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. + * + * 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: Levi Armstrong, Jens Petit */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h new file mode 100644 index 0000000000..177c093e6e --- /dev/null +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h @@ -0,0 +1,40 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD-2-Clause) + * + * Copyright (c) 2017, Southwest Research Institute + * 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. + * + * 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. + *********************************************************************/ + +/* Author: Levi Armstrong, Jens Petit */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h new file mode 100644 index 0000000000..be6f9c099e --- /dev/null +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h @@ -0,0 +1,40 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD-2-Clause) + * + * Copyright (c) 2017, Southwest Research Institute + * 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. + * + * 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. + *********************************************************************/ + +/* Author: Levi Armstrong, Jens Petit */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h new file mode 100644 index 0000000000..4ccf8f2152 --- /dev/null +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD-2-Clause) + * + * Copyright (c) 2017, Southwest Research Institute + * Copyright (c) 2013, John Schulman + * 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. + * + * 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: John Schulman, Levi Armstrong */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h new file mode 100644 index 0000000000..c429afe85f --- /dev/null +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h @@ -0,0 +1,27 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (Apache License) + * + * Copyright (c) 2017, Southwest Research Institute + * All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *********************************************************************/ + +/* Author: Levi Armstrong */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h new file mode 100644 index 0000000000..ccacba24d1 --- /dev/null +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h @@ -0,0 +1,27 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (Apache License) + * + * Copyright (c) 2018, Southwest Research Institute + * All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *********************************************************************/ + +/* Author: Levi Armstrong */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h new file mode 100644 index 0000000000..2e09d55218 --- /dev/null +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019, Jens Petit + * 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 the copyright holder 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. + *********************************************************************/ + +/* Author: Jens Petit */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h new file mode 100644 index 0000000000..3ad7034b0d --- /dev/null +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019, Jens Petit + * 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 the copyright holder 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. + *********************************************************************/ + +/* Author: Jens Petit */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h new file mode 100644 index 0000000000..9920a297d1 --- /dev/null +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019, Jens Petit + * 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 the copyright holder 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. + *********************************************************************/ + +/* Author: Jens Petit */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h new file mode 100644 index 0000000000..2356c90c28 --- /dev/null +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h new file mode 100644 index 0000000000..dd64c6aa51 --- /dev/null +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Acorn Pooley, Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h new file mode 100644 index 0000000000..02d98db6fb --- /dev/null +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Bryce Willey + * 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 the copyright holder 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. + *********************************************************************/ + +/* Author: Bryce Willey */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h new file mode 100644 index 0000000000..bb2c4cf3d3 --- /dev/null +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 the copyright holder 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. + *********************************************************************/ + +/* Author: Ioan Sucan, Jens Petit */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h new file mode 100644 index 0000000000..4b866aec57 --- /dev/null +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Hamburg 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Benjamin Scholz */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h new file mode 100644 index 0000000000..b557944298 --- /dev/null +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 the Willow Garage 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. + *********************************************************************/ + +/* Author: E. Gil Jones */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h new file mode 100644 index 0000000000..e2c906ca33 --- /dev/null +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Willow Garage, Inc. + * 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 the Willow Garage 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. + *********************************************************************/ + +/* Author: Acorn Pooley, Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h new file mode 100644 index 0000000000..655f7929d4 --- /dev/null +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Willow Garage, Inc. + * 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 the Willow Garage 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. + *********************************************************************/ + +/* Author: Acorn Pooley, Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h new file mode 100644 index 0000000000..836346946c --- /dev/null +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * 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 the Willow Garage 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. + *********************************************************************/ + +/* Author: E. Gil Jones */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h new file mode 100644 index 0000000000..88f8c90e03 --- /dev/null +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 the Willow Garage 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. + *********************************************************************/ + +/* Author: E. Gil Jones */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h new file mode 100644 index 0000000000..d631d928d5 --- /dev/null +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 the Willow Garage 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. + *********************************************************************/ + +/* Author: E. Gil Jones, Jens Petit */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h new file mode 100644 index 0000000000..773e5334b5 --- /dev/null +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h new file mode 100644 index 0000000000..0b39d90619 --- /dev/null +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h new file mode 100644 index 0000000000..331d2ce681 --- /dev/null +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h new file mode 100644 index 0000000000..5858f85871 --- /dev/null +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h new file mode 100644 index 0000000000..157e7e8ade --- /dev/null +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h new file mode 100644 index 0000000000..748a17ae36 --- /dev/null +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h b/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h new file mode 100644 index 0000000000..4be0a25300 --- /dev/null +++ b/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/distance_field/include/moveit/distance_field/distance_field.h b/moveit_core/distance_field/include/moveit/distance_field/distance_field.h new file mode 100644 index 0000000000..bc69c4e59b --- /dev/null +++ b/moveit_core/distance_field/include/moveit/distance_field/distance_field.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2009, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Mrinal Kalakrishnan, Ken Anderson, E. Gil Jones */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h b/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h new file mode 100644 index 0000000000..e6a0596ea4 --- /dev/null +++ b/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Acorn Pooley */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h b/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h new file mode 100644 index 0000000000..0aa607546b --- /dev/null +++ b/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2009, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Mrinal Kalakrishnan, Ken Anderson */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h b/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h new file mode 100644 index 0000000000..f671057f29 --- /dev/null +++ b/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2009, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Mrinal Kalakrishnan, Acorn Pooley */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h b/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h new file mode 100644 index 0000000000..24459297e9 --- /dev/null +++ b/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Sachin Chitta */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/exceptions/include/moveit/exceptions/exceptions.h b/moveit_core/exceptions/include/moveit/exceptions/exceptions.h new file mode 100644 index 0000000000..7b7de5bc08 --- /dev/null +++ b/moveit_core/exceptions/include/moveit/exceptions/exceptions.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Acorn Pooley, Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h new file mode 100644 index 0000000000..8a1088c414 --- /dev/null +++ b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h new file mode 100644 index 0000000000..192067fc81 --- /dev/null +++ b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h new file mode 100644 index 0000000000..6ad801d8ae --- /dev/null +++ b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Sachin Chitta, Dave Coleman */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h b/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h new file mode 100644 index 0000000000..6022c150f6 --- /dev/null +++ b/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Sachin Chitta */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/macros/include/moveit/macros/class_forward.h b/moveit_core/macros/include/moveit/macros/class_forward.h new file mode 100644 index 0000000000..861cfd90bb --- /dev/null +++ b/moveit_core/macros/include/moveit/macros/class_forward.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/macros/include/moveit/macros/console_colors.h b/moveit_core/macros/include/moveit/macros/console_colors.h new file mode 100644 index 0000000000..88cb4d0a3a --- /dev/null +++ b/moveit_core/macros/include/moveit/macros/console_colors.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/macros/include/moveit/macros/declare_ptr.h b/moveit_core/macros/include/moveit/macros/declare_ptr.h new file mode 100644 index 0000000000..32fc0be8be --- /dev/null +++ b/moveit_core/macros/include/moveit/macros/declare_ptr.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, Delft Robotics B.V. + * 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 the copyright holder 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/macros/include/moveit/macros/deprecation.h b/moveit_core/macros/include/moveit/macros/deprecation.h new file mode 100644 index 0000000000..cc4aea3ae5 --- /dev/null +++ b/moveit_core/macros/include/moveit/macros/deprecation.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h new file mode 100644 index 0000000000..50bb6569f8 --- /dev/null +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h @@ -0,0 +1,79 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2024, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/* Author: Paul Gesel +Description: applies smoothing by limiting the acceleration between consecutive commands. +The purpose of the plugin is to prevent the robot's acceleration limits from being violated by instantaneous changes +to the servo command topics. + + In the diagrams below, the c-v lines show the displacement that will occur given the current velocity. The t-c lines + shows the displacement between the current position and the desired position. The dashed lines shows the maximum + possible displacements that are within the acceleration limits. The v-t lines shows the acceleration commands that + will be used by this acceleration-limiting plugin. The x point shows the position that will be used for each scenario. + +Scenario A: The desired position is within the acceleration limits. The next commanded point will be exactly the +desired point. + ________ + | | +c --|-----xt | + \__|__ v | + |________| + +Scenario B: The line between the current position and the desired position intersects the acceleration limits, but the +reference position is not within the bounds. The next commanded point will be the point on the displacement line that +is closest to the reference. + ________ + | | +c --|--------x------t + \__|__ v | + |________| + +Scenario C: Neither the displacement line intersects the acceleration limits nor does the reference point lie within +the limits. In this case, the next commanded point will be the one that minimizes the robot's velocity while +maintaining its direction. + ________ + | | +c --------x--- v | + \ | | + \ |________| + t + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h new file mode 100644 index 0000000000..794aaeef77 --- /dev/null +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h @@ -0,0 +1,46 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/* Author: Andy Zelenak + Description: A first-order Butterworth low-pass filter. There is only one parameter to tune. + The first-order Butterworth filter has the nice property that it will not overshoot. + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h new file mode 100644 index 0000000000..70e3311fc7 --- /dev/null +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h @@ -0,0 +1,45 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2024, Andrew Zelenak + * 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 PickNik Inc. 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. + *********************************************************************/ + +/* Author: Andy Zelenak +Description: Applies jerk/acceleration/velocity limits to online motion commands + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h new file mode 100644 index 0000000000..ff8c44a743 --- /dev/null +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h @@ -0,0 +1,45 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/* Author: Andy Zelenak + Description: Defines a pluginlib interface for smoothing algorithms. + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h new file mode 100644 index 0000000000..3467b25339 --- /dev/null +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h new file mode 100644 index 0000000000..48a6830e35 --- /dev/null +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h new file mode 100644 index 0000000000..cd33af62a0 --- /dev/null +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h @@ -0,0 +1,45 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2023, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/* Author: Ioan Sucan, Sebastian Jahr + Description: Generic interface to adapting motion planning requests +*/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h new file mode 100644 index 0000000000..475ba83946 --- /dev/null +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h new file mode 100644 index 0000000000..b8d632baf8 --- /dev/null +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2023, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/* Author: Sebastian Jahr */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h new file mode 100644 index 0000000000..34f26636fb --- /dev/null +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan, Acorn Pooley */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/robot_model/include/moveit/robot_model/aabb.h b/moveit_core/robot_model/include/moveit/robot_model/aabb.h new file mode 100644 index 0000000000..a8141857da --- /dev/null +++ b/moveit_core/robot_model/include/moveit/robot_model/aabb.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Willow Garage, Inc. + * 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 Willow Garage, Inc. 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. + *********************************************************************/ + +/* Author: Martin Pecka */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h new file mode 100644 index 0000000000..6245343815 --- /dev/null +++ b/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Willow Garage, Inc. + * 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 Willow Garage, Inc. 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h new file mode 100644 index 0000000000..ef0f3cc4e9 --- /dev/null +++ b/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Willow Garage, Inc. + * 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 Willow Garage, Inc. 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/robot_model/include/moveit/robot_model/joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/joint_model.h new file mode 100644 index 0000000000..52bd598f99 --- /dev/null +++ b/moveit_core/robot_model/include/moveit/robot_model/joint_model.h @@ -0,0 +1,44 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Ioan A. Sucan + * Copyright (c) 2013, Willow Garage, Inc. + * 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 Willow Garage, Inc. 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h new file mode 100644 index 0000000000..c66b2dc5e0 --- /dev/null +++ b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h @@ -0,0 +1,44 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Ioan A. Sucan + * Copyright (c) 2008-2013, Willow Garage, Inc. + * 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 Willow Garage, Inc. 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/robot_model/include/moveit/robot_model/link_model.h b/moveit_core/robot_model/include/moveit/robot_model/link_model.h new file mode 100644 index 0000000000..5737099176 --- /dev/null +++ b/moveit_core/robot_model/include/moveit/robot_model/link_model.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Willow Garage, Inc. + * 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 Willow Garage, Inc. 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h new file mode 100644 index 0000000000..cae2778d5d --- /dev/null +++ b/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Willow Garage, Inc. + * 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 Willow Garage, Inc. 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h new file mode 100644 index 0000000000..e73f126fac --- /dev/null +++ b/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Willow Garage, Inc. + * 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 Willow Garage, Inc. 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h new file mode 100644 index 0000000000..1f4386ac44 --- /dev/null +++ b/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Willow Garage, Inc. + * 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 Willow Garage, Inc. 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h new file mode 100644 index 0000000000..5b85b5fac6 --- /dev/null +++ b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h @@ -0,0 +1,44 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Ioan A. Sucan + * Copyright (c) 2008-2013, Willow Garage, Inc. + * 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 Willow Garage, Inc. 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/robot_state/include/moveit/robot_state/attached_body.h b/moveit_core/robot_state/include/moveit/robot_state/attached_body.h new file mode 100644 index 0000000000..8dfe3d9815 --- /dev/null +++ b/moveit_core/robot_state/include/moveit/robot_state/attached_body.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage, Inc. 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h b/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h new file mode 100644 index 0000000000..9aeb91f1c6 --- /dev/null +++ b/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h @@ -0,0 +1,45 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Ioan A. Sucan + * Copyright (c) 2013, Willow Garage, Inc. + * Copyright (c) 2019, PickNik Inc. + * 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 Willow Garage, Inc. 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. + *********************************************************************/ + +/* Author: Ioan Sucan, Mike Lautman */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/robot_state/include/moveit/robot_state/conversions.h b/moveit_core/robot_state/include/moveit/robot_state/conversions.h new file mode 100644 index 0000000000..d447e36d7b --- /dev/null +++ b/moveit_core/robot_state/include/moveit/robot_state/conversions.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 the Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan, Dave Coleman */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h new file mode 100644 index 0000000000..f27b2c5405 --- /dev/null +++ b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h @@ -0,0 +1,44 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Ioan A. Sucan + * Copyright (c) 2013, Willow Garage, Inc. + * 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 Willow Garage, Inc. 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h new file mode 100644 index 0000000000..a9c1a06c14 --- /dev/null +++ b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan, Adam Leeper */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h new file mode 100644 index 0000000000..82659e4e97 --- /dev/null +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h @@ -0,0 +1,42 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/******************************************************************************* + * BSD 3-Clause License + * + * Copyright (c) 2021, PickNik Robotics + * 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 the copyright holder 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 HOLDER 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. + *******************************************************************************/ + +/* Author: Jack Center, Wyatt Rees, Andy Zelenak, Stephanie Eng */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h new file mode 100644 index 0000000000..68185fda6b --- /dev/null +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h @@ -0,0 +1,45 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/* + * Copyright (c) 2011-2012, Georgia Tech Research Corporation + * All rights reserved. + * + * Author: Tobias Kunz + * Date: 05/2012 + * + * Humanoid Robotics Lab Georgia Institute of Technology + * Director: Mike Stilman http://www.golems.org + * + * Algorithm details and publications: + * http://www.golems.org/node/1570 + * + * This file is provided under the following "BSD-style" License: + * 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. + * 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 HOLDER 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. + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h new file mode 100644 index 0000000000..3515b03f34 --- /dev/null +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h @@ -0,0 +1,7 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h new file mode 100644 index 0000000000..bcbd787f87 --- /dev/null +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/transforms/include/moveit/transforms/transforms.h b/moveit_core/transforms/include/moveit/transforms/transforms.h new file mode 100644 index 0000000000..98ada1074c --- /dev/null +++ b/moveit_core/transforms/include/moveit/transforms/transforms.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/utils/include/moveit/utils/eigen_test_utils.h b/moveit_core/utils/include/moveit/utils/eigen_test_utils.h new file mode 100644 index 0000000000..266c39d608 --- /dev/null +++ b/moveit_core/utils/include/moveit/utils/eigen_test_utils.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, Bielefeld 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 the 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. + *********************************************************************/ + +/* Author: Robert Haschke */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/utils/include/moveit/utils/lexical_casts.h b/moveit_core/utils/include/moveit/utils/lexical_casts.h new file mode 100644 index 0000000000..f419f9556a --- /dev/null +++ b/moveit_core/utils/include/moveit/utils/lexical_casts.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, isys vision, GmbH. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Simon Schmeisser */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/utils/include/moveit/utils/logger.h b/moveit_core/utils/include/moveit/utils/logger.h new file mode 100644 index 0000000000..337eb5035d --- /dev/null +++ b/moveit_core/utils/include/moveit/utils/logger.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2023, PickNik Robotics Inc. + * 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 PickNik Robotics Inc. 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. + *********************************************************************/ + +/* Author: Tyler Weaver */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/utils/include/moveit/utils/message_checks.h b/moveit_core/utils/include/moveit/utils/message_checks.h new file mode 100644 index 0000000000..9b2c1742a9 --- /dev/null +++ b/moveit_core/utils/include/moveit/utils/message_checks.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019, Universitaet Hamburg. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Michael 'v4hn' Goerner */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/utils/include/moveit/utils/moveit_error_code.h b/moveit_core/utils/include/moveit/utils/moveit_error_code.h new file mode 100644 index 0000000000..b312644c0c --- /dev/null +++ b/moveit_core/utils/include/moveit/utils/moveit_error_code.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik Inc. + * 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 the copyright holder 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/utils/include/moveit/utils/rclcpp_utils.h b/moveit_core/utils/include/moveit/utils/rclcpp_utils.h new file mode 100644 index 0000000000..e880425af4 --- /dev/null +++ b/moveit_core/utils/include/moveit/utils/rclcpp_utils.h @@ -0,0 +1,34 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/* + * Copyright (C) 2009, Willow Garage, Inc. + * + * 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 names of Willow Garage, Inc. 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. + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h b/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h new file mode 100644 index 0000000000..d8c182983f --- /dev/null +++ b/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h @@ -0,0 +1,44 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Bryce Willey. + * 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 MoveIt 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. + *********************************************************************/ + +/* Author: Bryce Willey */ +/** \brief convenience functions and classes used for making simple robot models for testing. */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h new file mode 100644 index 0000000000..86cb2c4665 --- /dev/null +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Rice 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 the Rice 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. + *********************************************************************/ + +/* Author: Mark Moll */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h new file mode 100644 index 0000000000..0b547c037e --- /dev/null +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Rice 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 the Rice 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. + *********************************************************************/ + +/* Author: Mark Moll */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h new file mode 100644 index 0000000000..3678f08e26 --- /dev/null +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h @@ -0,0 +1,45 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Rice 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 the Rice 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. + *********************************************************************/ + +/* Author: Mark Moll */ + +// This file is a slightly modified version of + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h new file mode 100644 index 0000000000..9574b89d87 --- /dev/null +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h @@ -0,0 +1,45 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * 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 the Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +// This file is a slightly modified version of + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h new file mode 100644 index 0000000000..977c010cbc --- /dev/null +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h @@ -0,0 +1,45 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Rice 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 the Rice 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. + *********************************************************************/ + +/* Author: Mark Moll, Bryant Gipson */ + +// This file is a slightly modified version of + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h new file mode 100644 index 0000000000..4ec23bf4a7 --- /dev/null +++ b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h @@ -0,0 +1,32 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +// Copyright (C) 2007 Ruben Smits + +// Version: 1.0 +// Author: Ruben Smits +// Maintainer: Ruben Smits +// URL: http://www.orocos.org/kdl + +// This library is free software; you can redistribute it and/or +// modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation; either +// version 2.1 of the License, or (at your option) any later version. + +// This library is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +// Lesser General Public License for more details. + +// You should have received a copy of the GNU Lesser General Public +// License along with this library; if not, write to the Free Software +// Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA + +// Modified to account for "mimic" joints, i.e. joints whose motion has a +// linear relationship to that of another joint. +// Copyright (C) 2013 Sachin Chitta, Willow Garage + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h new file mode 100644 index 0000000000..cda4dbaff8 --- /dev/null +++ b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Sachin Chitta */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h new file mode 100644 index 0000000000..c95ad1843b --- /dev/null +++ b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Sachin Chitta, David Lu!!, Ugo Cupcic */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h b/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h new file mode 100644 index 0000000000..ebd067b210 --- /dev/null +++ b/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h @@ -0,0 +1,48 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2014, JSK, The University of Tokyo. + * 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 JSK, The University of Tokyo 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. + *********************************************************************/ + +/* Author: Dave Coleman, Masaki Murooka + Desc: Connects MoveIt to any inverse kinematics solver via a ROS service call + Supports planning groups with multiple tip frames + \todo: better support for mimic joints + \todo: better support for redundant joints +*/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h new file mode 100644 index 0000000000..639bcdf035 --- /dev/null +++ b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: E. Gil Jones */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h new file mode 100644 index 0000000000..75c454d113 --- /dev/null +++ b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Chittaranjan Srinivas Swaminathan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h new file mode 100644 index 0000000000..6c223fbac6 --- /dev/null +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2009, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Mrinal Kalakrishnan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h new file mode 100644 index 0000000000..10a07f1252 --- /dev/null +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2009, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Mrinal Kalakrishnan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h new file mode 100644 index 0000000000..bf6ee51735 --- /dev/null +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h @@ -0,0 +1,46 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2009, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Mrinal Kalakrishnan */ + +#include +#include + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h new file mode 100644 index 0000000000..26872644f2 --- /dev/null +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: E. Gil Jones */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h new file mode 100644 index 0000000000..95a35559a9 --- /dev/null +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2009, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Mrinal Kalakrishnan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h new file mode 100644 index 0000000000..705a3de9e9 --- /dev/null +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2009, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Mrinal Kalakrishnan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h new file mode 100644 index 0000000000..3bdb099e23 --- /dev/null +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2009, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Mrinal Kalakrishnan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h new file mode 100644 index 0000000000..7e9f52de86 --- /dev/null +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h new file mode 100644 index 0000000000..9cadb32cd3 --- /dev/null +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h new file mode 100644 index 0000000000..dcc8c0c064 --- /dev/null +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h new file mode 100644 index 0000000000..5c2033387d --- /dev/null +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h new file mode 100644 index 0000000000..0fea7899c5 --- /dev/null +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h new file mode 100644 index 0000000000..5ea738a78a --- /dev/null +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2020, KU Leuven + * 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 KU Leuven 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. + *********************************************************************/ + +/* Author: Jeroen De Maeyer, Boston Cleek */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h new file mode 100644 index 0000000000..31b654086c --- /dev/null +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h new file mode 100644 index 0000000000..aafee34856 --- /dev/null +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h @@ -0,0 +1,54 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan, Jeroen De Maeyer */ + +/** A state validity checker checks: + * + * - Bounds (joint limits). + * - Collision. + * - Kinematic path constraints. + * - Generic user-specified feasibility using the `isStateFeasible` of the planning scene. + * + * IMPORTANT: Although the isValid method takes the state as `const ompl::base::State* state`, + * it uses const_cast to modify the validity of the state with `markInvalid` and `markValid` for caching. + * **/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h new file mode 100644 index 0000000000..4ff68592fe --- /dev/null +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h new file mode 100644 index 0000000000..061e0b57e4 --- /dev/null +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h new file mode 100644 index 0000000000..9f31737398 --- /dev/null +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h new file mode 100644 index 0000000000..233ac0cd71 --- /dev/null +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2020, KU Leuven + * 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 KU Leuven 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. + *********************************************************************/ + +/* Author: Jeroen De Maeyer */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h new file mode 100644 index 0000000000..84b63f5089 --- /dev/null +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h @@ -0,0 +1,44 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2020, KU Leuven + * 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 KU Leuven 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. + *********************************************************************/ + +/* Author: Jeroen De Maeyer */ +/* Mostly copied from Ioan Sucan's code */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h new file mode 100644 index 0000000000..86b5291779 --- /dev/null +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h new file mode 100644 index 0000000000..cc917bd480 --- /dev/null +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h new file mode 100644 index 0000000000..e50596bbc4 --- /dev/null +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h new file mode 100644 index 0000000000..55791b118c --- /dev/null +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h new file mode 100644 index 0000000000..7303005a72 --- /dev/null +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h new file mode 100644 index 0000000000..808935c0f1 --- /dev/null +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h new file mode 100644 index 0000000000..b8023396a9 --- /dev/null +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h new file mode 100644 index 0000000000..77122127b7 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h @@ -0,0 +1,23 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +// Copyright 2020 PAL Robotics S.L. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/// \author Adolfo Rodriguez Tsouroukdissian + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h new file mode 100644 index 0000000000..19fc8e076b --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h @@ -0,0 +1,23 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +// Copyright 2020 PAL Robotics S.L. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/// \author Adolfo Rodriguez Tsouroukdissian + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h new file mode 100644 index 0000000000..959363cce3 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h new file mode 100644 index 0000000000..197d0388ed --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h new file mode 100644 index 0000000000..01be7d7d0f --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h new file mode 100644 index 0000000000..0d11bf0d3b --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h new file mode 100644 index 0000000000..e33f3cc8d7 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h new file mode 100644 index 0000000000..dcd3eb1ce8 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h new file mode 100644 index 0000000000..0311151f3f --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h new file mode 100644 index 0000000000..f884727774 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h new file mode 100644 index 0000000000..f580813d58 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h new file mode 100644 index 0000000000..9fbd37c1cc --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h new file mode 100644 index 0000000000..f69562bba8 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h new file mode 100644 index 0000000000..a7b7ba223b --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h new file mode 100644 index 0000000000..ad0092e967 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h new file mode 100644 index 0000000000..258508917b --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h new file mode 100644 index 0000000000..c20d8d1d35 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h new file mode 100644 index 0000000000..81a68d6f37 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h new file mode 100644 index 0000000000..2acce916ab --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h new file mode 100644 index 0000000000..d322ee75f1 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h new file mode 100644 index 0000000000..9f79514e75 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h new file mode 100644 index 0000000000..5206f7dc39 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h new file mode 100644 index 0000000000..e2ea443d87 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h new file mode 100644 index 0000000000..ca1e3da75b --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h new file mode 100644 index 0000000000..30915e99f7 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h new file mode 100644 index 0000000000..b086348dbd --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h new file mode 100644 index 0000000000..493bf1c7a7 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h new file mode 100644 index 0000000000..f495ea3d7e --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h new file mode 100644 index 0000000000..62b7632853 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h new file mode 100644 index 0000000000..4339ae01c5 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h new file mode 100644 index 0000000000..1fc66b4c91 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h new file mode 100644 index 0000000000..f8df0f9c1e --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h new file mode 100644 index 0000000000..5005dbd9ef --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h new file mode 100644 index 0000000000..881abff6b5 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h new file mode 100644 index 0000000000..16ae95b819 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h new file mode 100644 index 0000000000..28c87ff119 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h new file mode 100644 index 0000000000..0a50693958 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h new file mode 100644 index 0000000000..0ee51b3609 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h new file mode 100644 index 0000000000..3c792ae663 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h @@ -0,0 +1,23 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/* + * Copyright (c) 2018 Pilz GmbH & Co. KG + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h new file mode 100644 index 0000000000..532440f973 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h new file mode 100644 index 0000000000..b7a861800f --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h new file mode 100644 index 0000000000..a461072e2b --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h new file mode 100644 index 0000000000..7fddb64c69 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h new file mode 100644 index 0000000000..aced99e0b9 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h new file mode 100644 index 0000000000..9d3190f47e --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h new file mode 100644 index 0000000000..076ff6505b --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h new file mode 100644 index 0000000000..470ef241bd --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h new file mode 100644 index 0000000000..2afffc78ff --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h new file mode 100644 index 0000000000..4e8b975710 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h new file mode 100644 index 0000000000..e28830f2bb --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h new file mode 100644 index 0000000000..4e296b2aec --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h new file mode 100644 index 0000000000..098cb3fb8e --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h new file mode 100644 index 0000000000..7475244c5e --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h new file mode 100644 index 0000000000..2d79c288c8 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h new file mode 100644 index 0000000000..85a909b1ef --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h new file mode 100644 index 0000000000..4c2c9e5d62 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h new file mode 100644 index 0000000000..a4c769826e --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h new file mode 100644 index 0000000000..4a403d0690 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h new file mode 100644 index 0000000000..07b70266b2 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h new file mode 100644 index 0000000000..4fcb9f97e1 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h new file mode 100644 index 0000000000..eed0a0e0ba --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h new file mode 100644 index 0000000000..1f5a941f50 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h new file mode 100644 index 0000000000..7acd682675 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h new file mode 100644 index 0000000000..c2bc798b77 --- /dev/null +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018 Pilz GmbH & Co. KG + * 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 Pilz GmbH & Co. KG 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h b/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h new file mode 100644 index 0000000000..9192be8134 --- /dev/null +++ b/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h @@ -0,0 +1,46 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2023, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/** @file + * @author Henning Kayser + * @brief Helper functions for converting between MoveIt types and plain Eigen types. + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/stomp/include/stomp_moveit/cost_functions.h b/moveit_planners/stomp/include/stomp_moveit/cost_functions.h new file mode 100644 index 0000000000..0e182d0d4a --- /dev/null +++ b/moveit_planners/stomp/include/stomp_moveit/cost_functions.h @@ -0,0 +1,46 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2023, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/** @file + * @author Henning Kayser + * @brief MoveIt-based cost functions that can be passed to STOMP via a ComposableTask. + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/stomp/include/stomp_moveit/filter_functions.h b/moveit_planners/stomp/include/stomp_moveit/filter_functions.h new file mode 100644 index 0000000000..485de47e98 --- /dev/null +++ b/moveit_planners/stomp/include/stomp_moveit/filter_functions.h @@ -0,0 +1,46 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2023, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/** @file + * @author Henning Kayser + * @brief Filter functions that can be passed to STOMP via a ComposableTask. + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h b/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h new file mode 100644 index 0000000000..a70d87409c --- /dev/null +++ b/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h @@ -0,0 +1,46 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2009, Willow Garage, Inc. + * 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 the Willow Garage 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. + *********************************************************************/ + +/** @file + * @author Mrinal Kalakrishnan + * @brief Implementation of a multi-variate Gaussian used for randomizing path waypoints + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/stomp/include/stomp_moveit/noise_generators.h b/moveit_planners/stomp/include/stomp_moveit/noise_generators.h new file mode 100644 index 0000000000..2c953203a9 --- /dev/null +++ b/moveit_planners/stomp/include/stomp_moveit/noise_generators.h @@ -0,0 +1,46 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2023, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/** @file + * @author Henning Kayser + * @brief Noise generator functions for randomizing trajectories in STOMP via a ComposableTask. + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h new file mode 100644 index 0000000000..00f559eacb --- /dev/null +++ b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h @@ -0,0 +1,46 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2023, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/** @file + * @author Henning Kayser + * @brief Planning Context implementation for STOMP + **/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h new file mode 100644 index 0000000000..96e98ee12e --- /dev/null +++ b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h @@ -0,0 +1,61 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2023, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/** @file + * @author Henning Kayser + * @brief A STOMP task definition that allows injecting custom functions for planning. + * + * STOMP's task interface can be used for customizing the planning objective, in particular the code used for sampling + * new random trajectories and for computing costs and validity of waypoint candidates. In order to allow building + * generic planning tasks at runtime, the ComposableTask class enables combining generic function types for planning: + * + * - NoiseGeneratorFn: computes randomized paths + * - CostFn: computes waypoint costs and path validity + * - FilterFn: applies a filter to path waypoints + * - PostIterationFn: reports on planning progress at each iteration (see STOMP documentation) + * - DoneFn: reports on planning result when STOMP run terminates + * + * Each of these functions use Eigen types for representing path and waypoints. + * The Eigen::MatrixXd 'values' refer to full path candidates where rows are the joint dimensions + * and columns are the waypoints. Accordingly, Eigen::VectorXd is used for representing cost values, + * one value for each waypoint. + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h b/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h new file mode 100644 index 0000000000..c68121c58a --- /dev/null +++ b/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h @@ -0,0 +1,46 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2023, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/** @file + * @author Henning Kayser + * @brief: Helper functions for visualizing trajectory markers for STOMP planning iterations. + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h b/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h new file mode 100644 index 0000000000..60e76e6dcd --- /dev/null +++ b/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2015, Fraunhofer IPA + * 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 Fraunhofer IPA 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. + *********************************************************************/ + +/* Author: Mathias Lüdtke */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h new file mode 100644 index 0000000000..b353f949ea --- /dev/null +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h @@ -0,0 +1,44 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Unbounded Robotics Inc. + * Copyright (c) 2012, Willow Garage, Inc. + * 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 the Willow Garage 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. + *********************************************************************/ + +/* Author: Michael Ferguson, Ioan Sucan, E. Gil Jones */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h new file mode 100644 index 0000000000..ee6603db3c --- /dev/null +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, PickNik Inc. + * 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 Fraunhofer IPA 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. + *********************************************************************/ + +/* Author: Paul Gesel */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h new file mode 100644 index 0000000000..c01770de36 --- /dev/null +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h @@ -0,0 +1,44 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Unbounded Robotics Inc. + * Copyright (c) 2012, Willow Garage, Inc. + * 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 the Willow Garage 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. + *********************************************************************/ + +/* Author: Michael Ferguson, Ioan Sucan, E. Gil Jones */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h new file mode 100644 index 0000000000..dc0eb46942 --- /dev/null +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h @@ -0,0 +1,44 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Unbounded Robotics Inc. + * Copyright (c) 2012, Willow Garage, Inc. + * 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 the Willow Garage 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. + *********************************************************************/ + +/* Author: Michael Ferguson, Ioan Sucan, E. Gil Jones */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h new file mode 100644 index 0000000000..4bcab94d93 --- /dev/null +++ b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, Peter David Fagan + * 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 PickNik Inc. 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. + *********************************************************************/ + +/* Author: Peter David Fagan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h new file mode 100644 index 0000000000..669fdb62b5 --- /dev/null +++ b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, Peter David Fagan, Robert Haschke + * 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. + * * The name of Robert Haschke may not be use 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. + *********************************************************************/ + +/* Author: Peter David Fagan, Robert Haschke */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h new file mode 100644 index 0000000000..1ec82739a5 --- /dev/null +++ b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2015, Rice 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 the Rice 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. + *********************************************************************/ + +/* Author: Ryan Luna */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h new file mode 100644 index 0000000000..abf731ece0 --- /dev/null +++ b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2015, Rice 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 the Rice 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. + *********************************************************************/ + +/* Author: Ryan Luna */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h new file mode 100644 index 0000000000..b2754cdd5e --- /dev/null +++ b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h @@ -0,0 +1,45 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/* Author: Sebastian Jahr + Description: A global planner component node that is customizable through plugins. + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h new file mode 100644 index 0000000000..494719293a --- /dev/null +++ b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h @@ -0,0 +1,46 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/* Author: Sebastian Jahr + Description: Defines an interface for a global motion planner plugin implementation used in the global planner + component node. + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h b/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h new file mode 100644 index 0000000000..fa6bfaca11 --- /dev/null +++ b/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h @@ -0,0 +1,44 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/* Author: Sebastian Jahr + Description: Global planner plugin that utilizes MoveIt's planning pipeline accessed via the MoveItCpp API*/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h new file mode 100644 index 0000000000..83d623d4cf --- /dev/null +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h @@ -0,0 +1,44 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2020, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/* Author: Sebastian Jahr + Description: Defines events that could occur during hybrid planning + */ +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h new file mode 100644 index 0000000000..7b713b35c0 --- /dev/null +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h @@ -0,0 +1,45 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2020, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/* Author: Sebastian Jahr + Description: The hybrid planning manager component node that serves as the control unit of the whole architecture. + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h new file mode 100644 index 0000000000..62dfb347da --- /dev/null +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h @@ -0,0 +1,45 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2020, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/* Author: Sebastian Jahr + Description: Defines an interface for a planner logic plugin for the hybrid planning manager component node. + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h new file mode 100644 index 0000000000..b64dc4f8a6 --- /dev/null +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h @@ -0,0 +1,47 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2020, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/* Author: Sebastian Jahr + Description: Simple hybrid planning logic that runs the global planner once and starts executing the global solution + with the local planner. In case the local planner detects a collision the global planner is rerun to update the + invalidated global trajectory. + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h new file mode 100644 index 0000000000..92b007c1b1 --- /dev/null +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h @@ -0,0 +1,46 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2020, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/* Author: Sebastian Jahr + Description: This planner logic plugin runs the global planner once and starts executing the global solution + with the local planner. + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h b/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h new file mode 100644 index 0000000000..67d51f012d --- /dev/null +++ b/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h @@ -0,0 +1,47 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2020, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/* Author: Sebastian Jahr + Description: Simple local solver plugin that forwards the next waypoint of the sampled local trajectory. + The local solver stops for two conditions: invalid waypoint (likely due to collision) or if it has been stuck for + several iterations. + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h new file mode 100644 index 0000000000..f023001145 --- /dev/null +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h @@ -0,0 +1,46 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/* Author: Andy Zelenak + Description: Define the expected local planner feedback types (usually equivalent to failure + modes). + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h new file mode 100644 index 0000000000..8f82285f8d --- /dev/null +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h @@ -0,0 +1,45 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2020, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/* Author: Sebastian Jahr + Description: Defines an interface for a local constraint solver plugin implementation for the local planner component node. + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h new file mode 100644 index 0000000000..fe6a9dccef --- /dev/null +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h @@ -0,0 +1,46 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2020, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/* Author: Sebastian Jahr + Description: A local planner component node that is customizable through plugins that implement the local planning + problem solver algorithm and the trajectory matching and blending. + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h new file mode 100644 index 0000000000..741a88d6c2 --- /dev/null +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h @@ -0,0 +1,45 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2020, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/* Author: Sebastian Jahr + Description: Defines an interface for a trajectory operator plugin implementation for the local planner component node. + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h b/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h new file mode 100644 index 0000000000..cc97cdf24f --- /dev/null +++ b/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h @@ -0,0 +1,47 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2020, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/* Author: Sebastian Jahr + Description: Simple trajectory operator that samples the next global trajectory waypoint as local goal constraint + based on the current robot state. When the waypoint is reached the index that marks the current local goal constraint + is updated to the next global trajectory waypoint. Global trajectory updates simply replace the reference trajectory. + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/move_group/include/moveit/move_group/capability_names.h b/moveit_ros/move_group/include/moveit/move_group/capability_names.h new file mode 100644 index 0000000000..020b349fe9 --- /dev/null +++ b/moveit_ros/move_group/include/moveit/move_group/capability_names.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h b/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h new file mode 100644 index 0000000000..d1dab0ab87 --- /dev/null +++ b/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/move_group/include/moveit/move_group/move_group_context.h b/moveit_ros/move_group/include/moveit/move_group/move_group_context.h new file mode 100644 index 0000000000..cdf9a1c161 --- /dev/null +++ b/moveit_ros/move_group/include/moveit/move_group/move_group_context.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h b/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h new file mode 100644 index 0000000000..0d42d8e946 --- /dev/null +++ b/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h @@ -0,0 +1,48 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/******************************************************************************* + * BSD 3-Clause License + * + * Copyright (c) 2019, Los Alamos National Security, LLC + * 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 the copyright holder 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 HOLDER 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. + *******************************************************************************/ +/* + * Title : collision_monitor.hpp + * Project : moveit_servo + * Created : 06/08/2023 + * Author : Brian O'Neil, Andy Zelenak, Blake Anderson, V Mohammed Ibrahim + * + * Description: Monitors the planning scene for collision and publishes the velocity scaling. + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/moveit_servo/include/moveit_servo/servo.h b/moveit_ros/moveit_servo/include/moveit_servo/servo.h new file mode 100644 index 0000000000..730570ccbb --- /dev/null +++ b/moveit_ros/moveit_servo/include/moveit_servo/servo.h @@ -0,0 +1,48 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/******************************************************************************* + * BSD 3-Clause License + * + * Copyright (c) 2019, Los Alamos National Security, LLC + * 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 the copyright holder 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 HOLDER 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. + *******************************************************************************/ + +/* Title : servo.hpp + * Project : moveit_servo + * Created : 05/17/2023 + * Author : Brian O'Neil, Andy Zelenak, Blake Anderson, V Mohammed Ibrahim + * + * Description : The core servoing logic. + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h b/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h new file mode 100644 index 0000000000..f0beef145b --- /dev/null +++ b/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h @@ -0,0 +1,48 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/******************************************************************************* + * BSD 3-Clause License + * + * Copyright (c) 2019, Los Alamos National Security, LLC + * 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 the copyright holder 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 HOLDER 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. + *******************************************************************************/ + +/* Title : servo_node.hpp + * Project : moveit_servo + * Created : 01/07/2023 + * Author : Brian O'Neil, Andy Zelenak, Blake Anderson, V Mohammed Ibrahim + * + * Description : The ROS API for Servo + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h b/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h new file mode 100644 index 0000000000..e79623a3cb --- /dev/null +++ b/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h @@ -0,0 +1,48 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/******************************************************************************* + * BSD 3-Clause License + * + * Copyright (c) 2019, Los Alamos National Security, LLC + * 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 the copyright holder 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 HOLDER 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. + *******************************************************************************/ + +/* Title : command.hpp + * Project : moveit_servo + * Created : 06/04/2023 + * Author : Brian O'Neil, Andy Zelenak, Blake Anderson, V Mohammed Ibrahim + * + * Description : The methods that compute the required change in joint angles for various input types. + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h b/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h new file mode 100644 index 0000000000..dfbae7c03a --- /dev/null +++ b/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h @@ -0,0 +1,48 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/******************************************************************************* + * BSD 3-Clause License + * + * Copyright (c) 2019, Los Alamos National Security, LLC + * 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 the copyright holder 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 HOLDER 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. + *******************************************************************************/ + +/* Title : utils.hpp + * Project : moveit_servo + * Created : 05/17/2023 + * Author : Andy Zelenak, V Mohammed Ibrahim + * + * Description : The utility functions used by MoveIt Servo. + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h b/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h new file mode 100644 index 0000000000..f9896e5020 --- /dev/null +++ b/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h @@ -0,0 +1,48 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/******************************************************************************* + * BSD 3-Clause License + * + * Copyright (c) 2019, Los Alamos National Security, LLC + * 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 the copyright holder 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 HOLDER 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. + *******************************************************************************/ + +/* Title : datatypes.hpp + * Project : moveit_servo + * Created : 06/05/2023 + * Author : Andy Zelenak, V Mohammed Ibrahim + * + * Description : The custom datatypes used by Moveit Servo. + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h new file mode 100644 index 0000000000..7e451498ee --- /dev/null +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan, Jon Binney */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h new file mode 100644 index 0000000000..c85f95e170 --- /dev/null +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik, Inc. + * 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 PickNik 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. + *********************************************************************/ + +/* Author: Tyler Weaver */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h new file mode 100644 index 0000000000..d0037c7434 --- /dev/null +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan, Jon Binney */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h b/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h new file mode 100644 index 0000000000..03ee2c13f4 --- /dev/null +++ b/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h b/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h new file mode 100644 index 0000000000..cf97b37edd --- /dev/null +++ b/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h new file mode 100644 index 0000000000..d0ec48091c --- /dev/null +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Suat Gedikli */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h new file mode 100644 index 0000000000..8c8af8af6c --- /dev/null +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Suat Gedikli */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h new file mode 100644 index 0000000000..651291530b --- /dev/null +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Suat Gedikli */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h new file mode 100644 index 0000000000..745bf521b9 --- /dev/null +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Suat Gedikli */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h new file mode 100644 index 0000000000..392c0406c6 --- /dev/null +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Suat Gedikli */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h new file mode 100644 index 0000000000..9def272c3d --- /dev/null +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Suat Gedikli */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h new file mode 100644 index 0000000000..ee9242bfd0 --- /dev/null +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Suat Gedikli */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h new file mode 100644 index 0000000000..067ea22553 --- /dev/null +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Suat Gedikli */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h new file mode 100644 index 0000000000..1ef6d2607b --- /dev/null +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Suat Gedikli */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h b/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h new file mode 100644 index 0000000000..affa78a63f --- /dev/null +++ b/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h b/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h new file mode 100644 index 0000000000..e1e6e0aa74 --- /dev/null +++ b/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Jon Binney, Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h new file mode 100644 index 0000000000..da53fdf2a7 --- /dev/null +++ b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Sachin Chitta */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h b/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h new file mode 100644 index 0000000000..83fca003d6 --- /dev/null +++ b/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2014 Fetch Robotics Inc. + * 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 Fetch Robotics 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h b/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h new file mode 100644 index 0000000000..098e210e94 --- /dev/null +++ b/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h b/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h new file mode 100644 index 0000000000..2d5163ca79 --- /dev/null +++ b/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan, Dave Coleman */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h new file mode 100644 index 0000000000..d531f1a1aa --- /dev/null +++ b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h @@ -0,0 +1,46 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/* Author: Henning Kayser + Desc: A high level interface that does not require the use of ROS Actions, Services, and Messages to access the + core MoveIt functionality +*/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h new file mode 100644 index 0000000000..385604182d --- /dev/null +++ b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h @@ -0,0 +1,44 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/* Author: Henning Kayser + Desc: API for planning and execution capabilities of a JointModelGroup */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h new file mode 100644 index 0000000000..dca5dfad5f --- /dev/null +++ b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h new file mode 100644 index 0000000000..36538d338b --- /dev/null +++ b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h new file mode 100644 index 0000000000..c24d9f9f51 --- /dev/null +++ b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h @@ -0,0 +1,46 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan, Sebastian Jahr + Description: Implementation of a MoveIt planning pipeline composed of a planner plugin and request and response + adapter plugins. +*/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h new file mode 100644 index 0000000000..449da27c26 --- /dev/null +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h @@ -0,0 +1,44 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2023, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/* Author: Sebastian Jahr + Desc: A thread safe container to store motion plan responses */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h new file mode 100644 index 0000000000..6b47385bc7 --- /dev/null +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h @@ -0,0 +1,44 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2023, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/* Author: Sebastian Jahr + Desc: Functions to create and use a map of PlanningPipelines to solve MotionPlanRequests */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h new file mode 100644 index 0000000000..fbd1ae637d --- /dev/null +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h @@ -0,0 +1,44 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2023, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/* Author: Sebastian Jahr + Desc: Solution selection function implementations */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h new file mode 100644 index 0000000000..17553d4b54 --- /dev/null +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h @@ -0,0 +1,44 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2023, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/* Author: AndyZe, Sebastian Jahr + Desc: Stopping criterion function implementations */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h new file mode 100644 index 0000000000..57a934f6f7 --- /dev/null +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h new file mode 100644 index 0000000000..144ab44929 --- /dev/null +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik, Inc. + * 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 PickNik 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. + *********************************************************************/ + +/* Author: Tyler Weaver */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h new file mode 100644 index 0000000000..d5b1b30187 --- /dev/null +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h new file mode 100644 index 0000000000..301cc55cea --- /dev/null +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h new file mode 100644 index 0000000000..70a937d801 --- /dev/null +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik, Inc. + * 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 PickNik 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. + *********************************************************************/ + +/* Author: Abishalini Sivaraman */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h new file mode 100644 index 0000000000..23173dd5c0 --- /dev/null +++ b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan, Mathias Lüdtke, Dave Coleman */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h new file mode 100644 index 0000000000..74d375e661 --- /dev/null +++ b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik Robotics + * 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 PickNik Robotics 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h b/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h new file mode 100644 index 0000000000..b4ca0a94c9 --- /dev/null +++ b/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h new file mode 100644 index 0000000000..e152c2f995 --- /dev/null +++ b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h b/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h new file mode 100644 index 0000000000..1be2600088 --- /dev/null +++ b/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h new file mode 100644 index 0000000000..59b3c6a9ef --- /dev/null +++ b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h @@ -0,0 +1,44 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2014, SRI International + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan, Sachin Chitta */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h b/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h new file mode 100644 index 0000000000..3cf28a748c --- /dev/null +++ b/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h new file mode 100644 index 0000000000..a2400a12a0 --- /dev/null +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2014, SRI International + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Acorn Pooley */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h new file mode 100644 index 0000000000..5f830e4558 --- /dev/null +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan, Adam Leeper */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h new file mode 100644 index 0000000000..32500010c8 --- /dev/null +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan, Acorn Pooley, Adam Leeper */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h new file mode 100644 index 0000000000..7034b604f7 --- /dev/null +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2014, SRI International + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Acorn Pooley */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h new file mode 100644 index 0000000000..d7ed065d6e --- /dev/null +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2014, SRI International + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Acorn Pooley */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h new file mode 100644 index 0000000000..5eeb5b0909 --- /dev/null +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h @@ -0,0 +1,44 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * Copyright (c) 2014, SRI International + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan, Acorn Pooley */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h new file mode 100644 index 0000000000..a004d717b2 --- /dev/null +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan, Adam Leeper */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/tests/include/parameter_name_list.h b/moveit_ros/tests/include/parameter_name_list.h new file mode 100644 index 0000000000..a07e682049 --- /dev/null +++ b/moveit_ros/tests/include/parameter_name_list.h @@ -0,0 +1,46 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2024, PickNik Inc. + * 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 PickNik Inc. 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. + *********************************************************************/ + +/* Author: Sebastian Jahr + Description: List of all parameter names used when move_group with OMPL, CHOMP, STOMP and PILZ is launched (01/2024). +*/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h b/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h new file mode 100644 index 0000000000..1afa9736a5 --- /dev/null +++ b/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h @@ -0,0 +1,26 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +// Copyright 2024 Intrinsic Innovation LLC. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/** @file + * @brief Fuzzy-Matching Trajectory Cache. + * @author methylDragon + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h new file mode 100644 index 0000000000..119e152141 --- /dev/null +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h @@ -0,0 +1,42 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/* + * Copyright (c) 2008, Willow Garage, Inc. + * Copyright (c) 2019, Open Source Robotics Foundation, Inc. + * 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 the copyright holder 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. + */ + +// TODO(JafarAbdi): Remove this file once the lag issue is fixed upstream https://github.com/ros2/rviz/issues/548 +// This file is copied from https://github.com/ros2/rviz, the only difference is the addition of the private members +// pnode_, private_executor_, and private_executor_thread_ to fix the lag in the motion planning display interactive +// marker cause by Rviz having only a single thread executor + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h new file mode 100644 index 0000000000..b768d91b93 --- /dev/null +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan, Dave Coleman, Adam Leeper, Sachin Chitta */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h new file mode 100644 index 0000000000..d7642070ac --- /dev/null +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h new file mode 100644 index 0000000000..572b1cbdda --- /dev/null +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019, CITEC, Bielefeld 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 CITEC / 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. + *********************************************************************/ + +/* Author: Robert Haschke */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h new file mode 100644 index 0000000000..4ab18f0bd1 --- /dev/null +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Robert Haschke */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h new file mode 100644 index 0000000000..0d336bd172 --- /dev/null +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h new file mode 100644 index 0000000000..3aaa591487 --- /dev/null +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h b/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h new file mode 100644 index 0000000000..f69005ec71 --- /dev/null +++ b/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h new file mode 100644 index 0000000000..944fa57a7d --- /dev/null +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Julius Kammerl */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h new file mode 100644 index 0000000000..f6d8a754c7 --- /dev/null +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h new file mode 100644 index 0000000000..e3f34928c8 --- /dev/null +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h new file mode 100644 index 0000000000..6b11519597 --- /dev/null +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h new file mode 100644 index 0000000000..c3ba555b9e --- /dev/null +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h new file mode 100644 index 0000000000..cff0f4a4ed --- /dev/null +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Yannick Jonetzko + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Yannick Jonetzko */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h new file mode 100644 index 0000000000..1366ae7054 --- /dev/null +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Dave Coleman */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h new file mode 100644 index 0000000000..c2fedc2bcc --- /dev/null +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h @@ -0,0 +1,36 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/* + * Copyright (c) 2008, Willow Garage, Inc. + * 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 the Willow Garage, Inc. 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. + */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h b/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h new file mode 100644 index 0000000000..bb983d620b --- /dev/null +++ b/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h @@ -0,0 +1,45 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2015, University of Colorado, Boulder + * 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 the Univ of CO, Boulder 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. + *********************************************************************/ + +/* Author: Dave Coleman + Desc: Wraps a trajectory_visualization playback class for Rviz into a stand alone display +*/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h new file mode 100644 index 0000000000..0d992cdf91 --- /dev/null +++ b/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h new file mode 100644 index 0000000000..c07a736278 --- /dev/null +++ b/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h new file mode 100644 index 0000000000..dc9101f881 --- /dev/null +++ b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h new file mode 100644 index 0000000000..32dd86efd9 --- /dev/null +++ b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h new file mode 100644 index 0000000000..21845f13fc --- /dev/null +++ b/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h new file mode 100644 index 0000000000..92064644e2 --- /dev/null +++ b/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Mario Prats, Ioan Sucan */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h b/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h new file mode 100644 index 0000000000..5d2ab6ab7f --- /dev/null +++ b/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: E. Gil Jones */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h new file mode 100644 index 0000000000..0a90012a9e --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h @@ -0,0 +1,42 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, Metro Robots + * 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 Metro Robots 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h new file mode 100644 index 0000000000..819fe74b74 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h @@ -0,0 +1,42 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, Metro Robots + * 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 Metro Robots 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h new file mode 100644 index 0000000000..7f513d7c44 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h @@ -0,0 +1,42 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, Metro Robots + * 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 Metro Robots 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h new file mode 100644 index 0000000000..f9e7e70a04 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h @@ -0,0 +1,42 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, Metro Robots + * 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 Metro Robots 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h new file mode 100644 index 0000000000..ec9fc89d4f --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h @@ -0,0 +1,42 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik Robotics + * 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 PickNik Robotics 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h new file mode 100644 index 0000000000..ae8dba7e22 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h @@ -0,0 +1,42 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik Robotics + * 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 PickNik Robotics 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h new file mode 100644 index 0000000000..6790825398 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h @@ -0,0 +1,42 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Mohamad Ayman. + * 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. + * * The name of Mohamad Ayman may not 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. + *********************************************************************/ + +/* Author: Mohamad Ayman */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h new file mode 100644 index 0000000000..c35197d581 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Dave Coleman */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h new file mode 100644 index 0000000000..c15a6f0208 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Dave Coleman */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h new file mode 100644 index 0000000000..4f5b473cdb --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, Metro Robots + * 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 Metro Robots 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h new file mode 100644 index 0000000000..16a637cffc --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h @@ -0,0 +1,42 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Mohamad Ayman. + * 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. + * * The name of Mohamad Ayman 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. + *********************************************************************/ + +/* Author: Mohamad Ayman */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h new file mode 100644 index 0000000000..ecc4d74d94 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h @@ -0,0 +1,42 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik Robotics + * 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 PickNik Robotics 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h new file mode 100644 index 0000000000..ffe3f0efb7 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h @@ -0,0 +1,42 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, Metro Robots + * 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 Metro Robots 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h new file mode 100644 index 0000000000..c6904e12be --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h @@ -0,0 +1,42 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Mohamad Ayman. + * 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. + * * The name of Mohamad Ayman 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. + *********************************************************************/ + +/* Author: Mohamad Ayman */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h new file mode 100644 index 0000000000..e0198f8711 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, Metro Robots + * 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 Metro Robots 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h new file mode 100644 index 0000000000..d785dcd0fb --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, Metro Robots + * 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 Metro Robots 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h new file mode 100644 index 0000000000..7973ed5fa5 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik Robotics + * 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 PickNik Robotics 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h new file mode 100644 index 0000000000..9b6016c32f --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, Metro Robots + * 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 Metro Robots 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h new file mode 100644 index 0000000000..97bb0fef75 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, Metro Robots + * 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 Metro Robots 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h new file mode 100644 index 0000000000..272099d1c8 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, Metro Robots + * 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 Metro Robots 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h new file mode 100644 index 0000000000..888dd2a3c3 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h @@ -0,0 +1,42 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, Metro Robots + * 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 Metro Robots 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h new file mode 100644 index 0000000000..e29e86716e --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, Metro Robots + * 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 Metro Robots 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h new file mode 100644 index 0000000000..b3c8ae4adb --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h @@ -0,0 +1,42 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik Robotics + * 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 PickNik Robotics 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h new file mode 100644 index 0000000000..ea3f582823 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Dave Coleman, Michael 'v4hn' Goerner */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h new file mode 100644 index 0000000000..57dea204e6 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h new file mode 100644 index 0000000000..8e380c5bdb --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Dave Coleman */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h new file mode 100644 index 0000000000..18ddd400e1 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h new file mode 100644 index 0000000000..07516d35aa --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Dave Coleman */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h new file mode 100644 index 0000000000..1f783c1078 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik Robotics + * 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 PickNik Robotics 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h new file mode 100644 index 0000000000..b68405df3a --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik Robotics, Inc. + * 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 PickNik Robotics 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h new file mode 100644 index 0000000000..00c14f1242 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h @@ -0,0 +1,42 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik Robotics, Inc. + * 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 PickNik Robotics 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h new file mode 100644 index 0000000000..12b8dc83ac --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h @@ -0,0 +1,41 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik Robotics, Inc. + * 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 PickNik Robotics 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. + *********************************************************************/ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h new file mode 100644 index 0000000000..f245c04234 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h @@ -0,0 +1,49 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik Robotics + * 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 PickNik Robotics 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ + +#include +#include +#include +#include +#include + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h new file mode 100644 index 0000000000..2340d51176 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik Robotics + * 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 PickNik Robotics 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h new file mode 100644 index 0000000000..48e0195235 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, Metro Robots + * 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 Metro Robots 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h new file mode 100644 index 0000000000..6bf4d21261 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Dave Coleman */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h new file mode 100644 index 0000000000..1a3e3957da --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Dave Coleman */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h new file mode 100644 index 0000000000..17e38b27a2 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik Robotics + * 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 PickNik Robotics 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h new file mode 100644 index 0000000000..0bdbe083e9 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Dave Coleman */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h new file mode 100644 index 0000000000..f323cfaabf --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, Bielefeld University, Inc. + * 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. + *********************************************************************/ + +/* Author: Robert Haschke */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h new file mode 100644 index 0000000000..5bc90726e7 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik Robotics + * 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 PickNik Robotics 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h new file mode 100644 index 0000000000..41a2b80d3e --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h @@ -0,0 +1,42 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik Robotics, Inc. + * 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 PickNik Robotics 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h new file mode 100644 index 0000000000..9cbec2d37c --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, Metro Robots + * 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 Metro Robots 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h new file mode 100644 index 0000000000..8aff3d4627 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik Robotics + * 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 PickNik Robotics 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h new file mode 100644 index 0000000000..4d1ff8dde8 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h @@ -0,0 +1,42 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik Robotics + * 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 PickNik Robotics 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h new file mode 100644 index 0000000000..d1a6e08bf5 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h @@ -0,0 +1,42 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Mohamad Ayman. + * 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. + * * The name of Mohamad Ayman may not 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. + *********************************************************************/ + +/* Author: Mohamad Ayman */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h new file mode 100644 index 0000000000..01088c4108 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, CITEC, Bielefeld 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Robert Haschke */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h new file mode 100644 index 0000000000..0389fdcda4 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, CITEC, Bielefeld 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Robert Haschke */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h new file mode 100644 index 0000000000..6b30d39d8d --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Dave Coleman */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h new file mode 100644 index 0000000000..ccb3c9bd92 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h @@ -0,0 +1,42 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik Robotics + * 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 PickNik Robotics 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h new file mode 100644 index 0000000000..cbed5d9f5d --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Dave Coleman */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h new file mode 100644 index 0000000000..d79cd30ff4 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h @@ -0,0 +1,42 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik Robotics + * 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 PickNik Robotics 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h new file mode 100644 index 0000000000..3b5139e69a --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Dave Coleman */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h new file mode 100644 index 0000000000..e15d52b9f0 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Dave Coleman */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h new file mode 100644 index 0000000000..51d73589e7 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h @@ -0,0 +1,42 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, Metro Robots + * 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 Metro Robots 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h new file mode 100644 index 0000000000..ba8ec5ae06 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Dave Coleman */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h new file mode 100644 index 0000000000..82d916279d --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h @@ -0,0 +1,42 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik Robotics + * 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 PickNik Robotics 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h new file mode 100644 index 0000000000..1bcceba81e --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Dave Coleman */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h new file mode 100644 index 0000000000..57c6a260e0 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h @@ -0,0 +1,42 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik Robotics + * 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 PickNik Robotics 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h new file mode 100644 index 0000000000..191a88b4cc --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Dave Coleman */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h new file mode 100644 index 0000000000..947fcc4204 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h @@ -0,0 +1,42 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik Robotics + * 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 PickNik Robotics 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h new file mode 100644 index 0000000000..7b4f8055ff --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Dave Coleman */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h new file mode 100644 index 0000000000..4700d6c9c8 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, CITEC, Bielefeld 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Robert Haschke */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h new file mode 100644 index 0000000000..b40885060d --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h @@ -0,0 +1,42 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, Metro Robots + * 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 Metro Robots 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h new file mode 100644 index 0000000000..e49a70b6b2 --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h @@ -0,0 +1,42 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2021, PickNik Robotics + * 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 PickNik Robotics 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. + *********************************************************************/ + +/* Author: David V. Lu!! */ +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h new file mode 100644 index 0000000000..30928bbc3c --- /dev/null +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h @@ -0,0 +1,43 @@ +This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * 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 Willow Garage 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. + *********************************************************************/ + +/* Author: Dave Coleman */ + +#pragma once + +#pragma message(".h header is obsolete. Please use the .hpp") + +#include \ No newline at end of file From bd16103b3ce60fddabdf47c7fcdf2b8642708269 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Thu, 21 Nov 2024 17:53:57 +0000 Subject: [PATCH 39/53] Applies formatting --- .../allvalid/collision_detector_allocator_allvalid.h | 4 ++-- .../collision_detection/allvalid/collision_env_allvalid.h | 4 ++-- .../include/moveit/collision_detection/collision_common.h | 4 ++-- .../collision_detection/collision_detector_allocator.h | 4 ++-- .../include/moveit/collision_detection/collision_env.h | 4 ++-- .../include/moveit/collision_detection/collision_matrix.h | 4 ++-- .../moveit/collision_detection/collision_octomap_filter.h | 4 ++-- .../include/moveit/collision_detection/collision_plugin.h | 4 ++-- .../moveit/collision_detection/collision_plugin_cache.h | 4 ++-- .../include/moveit/collision_detection/collision_tools.h | 4 ++-- .../include/moveit/collision_detection/occupancy_map.h | 4 ++-- .../moveit/collision_detection/test_collision_common_panda.h | 4 ++-- .../moveit/collision_detection/test_collision_common_pr2.h | 4 ++-- .../include/moveit/collision_detection/world.h | 4 ++-- .../include/moveit/collision_detection/world_diff.h | 4 ++-- .../bullet_integration/basic_types.h | 4 ++-- .../bullet_integration/bullet_bvh_manager.h | 4 ++-- .../bullet_integration/bullet_cast_bvh_manager.h | 4 ++-- .../bullet_integration/bullet_discrete_bvh_manager.h | 4 ++-- .../bullet_integration/bullet_utils.h | 4 ++-- .../bullet_integration/contact_checker_common.h | 4 ++-- .../bullet_integration/ros_bullet_utils.h | 4 ++-- .../collision_detector_allocator_bullet.h | 4 ++-- .../collision_detector_bullet_plugin_loader.h | 4 ++-- .../moveit/collision_detection_bullet/collision_env_bullet.h | 4 ++-- .../moveit/collision_detection_fcl/collision_common.h | 4 ++-- .../collision_detector_allocator_fcl.h | 4 ++-- .../collision_detector_fcl_plugin_loader.h | 4 ++-- .../moveit/collision_detection_fcl/collision_env_fcl.h | 4 ++-- .../include/moveit/collision_detection_fcl/fcl_compat.h | 4 ++-- .../collision_common_distance_field.h | 4 ++-- .../collision_detector_allocator_distance_field.h | 4 ++-- .../collision_detector_allocator_hybrid.h | 4 ++-- .../collision_distance_field_types.h | 4 ++-- .../collision_distance_field/collision_env_distance_field.h | 4 ++-- .../moveit/collision_distance_field/collision_env_hybrid.h | 4 ++-- .../include/moveit/constraint_samplers/constraint_sampler.h | 4 ++-- .../constraint_samplers/constraint_sampler_allocator.h | 4 ++-- .../moveit/constraint_samplers/constraint_sampler_manager.h | 4 ++-- .../moveit/constraint_samplers/constraint_sampler_tools.h | 4 ++-- .../moveit/constraint_samplers/default_constraint_samplers.h | 4 ++-- .../moveit/constraint_samplers/union_constraint_sampler.h | 4 ++-- .../include/moveit/controller_manager/controller_manager.h | 4 ++-- .../include/moveit/distance_field/distance_field.h | 4 ++-- .../include/moveit/distance_field/find_internal_points.h | 4 ++-- .../moveit/distance_field/propagation_distance_field.h | 4 ++-- .../include/moveit/distance_field/voxel_grid.h | 4 ++-- .../include/moveit/dynamics_solver/dynamics_solver.h | 4 ++-- .../exceptions/include/moveit/exceptions/exceptions.h | 4 ++-- .../moveit/kinematic_constraints/kinematic_constraint.h | 4 ++-- .../include/moveit/kinematic_constraints/utils.h | 4 ++-- .../include/moveit/kinematics_base/kinematics_base.h | 4 ++-- .../include/moveit/kinematics_metrics/kinematics_metrics.h | 4 ++-- moveit_core/macros/include/moveit/macros/class_forward.h | 4 ++-- moveit_core/macros/include/moveit/macros/console_colors.h | 4 ++-- moveit_core/macros/include/moveit/macros/declare_ptr.h | 4 ++-- moveit_core/macros/include/moveit/macros/deprecation.h | 4 ++-- .../moveit/online_signal_smoothing/acceleration_filter.h | 4 ++-- .../moveit/online_signal_smoothing/butterworth_filter.h | 4 ++-- .../include/moveit/online_signal_smoothing/ruckig_filter.h | 4 ++-- .../moveit/online_signal_smoothing/smoothing_base_class.h | 4 ++-- .../include/moveit/planning_interface/planning_interface.h | 4 ++-- .../include/moveit/planning_interface/planning_request.h | 4 ++-- .../moveit/planning_interface/planning_request_adapter.h | 4 ++-- .../include/moveit/planning_interface/planning_response.h | 4 ++-- .../moveit/planning_interface/planning_response_adapter.h | 4 ++-- .../include/moveit/planning_scene/planning_scene.h | 4 ++-- moveit_core/robot_model/include/moveit/robot_model/aabb.h | 4 ++-- .../include/moveit/robot_model/fixed_joint_model.h | 4 ++-- .../include/moveit/robot_model/floating_joint_model.h | 4 ++-- .../robot_model/include/moveit/robot_model/joint_model.h | 4 ++-- .../include/moveit/robot_model/joint_model_group.h | 4 ++-- .../robot_model/include/moveit/robot_model/link_model.h | 4 ++-- .../include/moveit/robot_model/planar_joint_model.h | 4 ++-- .../include/moveit/robot_model/prismatic_joint_model.h | 4 ++-- .../include/moveit/robot_model/revolute_joint_model.h | 4 ++-- .../robot_model/include/moveit/robot_model/robot_model.h | 4 ++-- .../robot_state/include/moveit/robot_state/attached_body.h | 4 ++-- .../include/moveit/robot_state/cartesian_interpolator.h | 4 ++-- .../robot_state/include/moveit/robot_state/conversions.h | 4 ++-- .../robot_state/include/moveit/robot_state/robot_state.h | 4 ++-- .../include/moveit/robot_trajectory/robot_trajectory.h | 4 ++-- .../moveit/trajectory_processing/ruckig_traj_smoothing.h | 4 ++-- .../time_optimal_trajectory_generation.h | 4 ++-- .../moveit/trajectory_processing/time_parameterization.h | 4 ++-- .../include/moveit/trajectory_processing/trajectory_tools.h | 4 ++-- .../transforms/include/moveit/transforms/transforms.h | 4 ++-- moveit_core/utils/include/moveit/utils/eigen_test_utils.h | 4 ++-- moveit_core/utils/include/moveit/utils/lexical_casts.h | 4 ++-- moveit_core/utils/include/moveit/utils/logger.h | 4 ++-- moveit_core/utils/include/moveit/utils/message_checks.h | 4 ++-- moveit_core/utils/include/moveit/utils/moveit_error_code.h | 4 ++-- moveit_core/utils/include/moveit/utils/rclcpp_utils.h | 4 ++-- .../utils/include/moveit/utils/robot_model_test_utils.h | 4 ++-- .../cached_ik_kinematics_plugin-inl.h | 4 ++-- .../cached_ik_kinematics_plugin.h | 4 ++-- .../cached_ik_kinematics_plugin/detail/GreedyKCenters.h | 4 ++-- .../cached_ik_kinematics_plugin/detail/NearestNeighbors.h | 4 ++-- .../detail/NearestNeighborsGNAT.h | 4 ++-- .../kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h | 4 ++-- .../include/moveit/kdl_kinematics_plugin/joint_mimic.h | 4 ++-- .../moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h | 4 ++-- .../moveit/srv_kinematics_plugin/srv_kinematics_plugin.h | 4 ++-- .../include/chomp_interface/chomp_interface.h | 4 ++-- .../include/chomp_interface/chomp_planning_context.h | 4 ++-- .../include/chomp_motion_planner/chomp_cost.h | 4 ++-- .../include/chomp_motion_planner/chomp_optimizer.h | 4 ++-- .../include/chomp_motion_planner/chomp_parameters.h | 4 ++-- .../include/chomp_motion_planner/chomp_planner.h | 4 ++-- .../include/chomp_motion_planner/chomp_trajectory.h | 4 ++-- .../include/chomp_motion_planner/chomp_utils.h | 4 ++-- .../include/chomp_motion_planner/multivariate_gaussian.h | 4 ++-- .../moveit/ompl_interface/detail/constrained_goal_sampler.h | 4 ++-- .../moveit/ompl_interface/detail/constrained_sampler.h | 4 ++-- .../moveit/ompl_interface/detail/constraint_approximations.h | 4 ++-- .../moveit/ompl_interface/detail/constraints_library.h | 4 ++-- .../include/moveit/ompl_interface/detail/goal_union.h | 4 ++-- .../include/moveit/ompl_interface/detail/ompl_constraints.h | 4 ++-- .../moveit/ompl_interface/detail/projection_evaluators.h | 4 ++-- .../moveit/ompl_interface/detail/state_validity_checker.h | 4 ++-- .../moveit/ompl_interface/detail/threadsafe_state_storage.h | 4 ++-- .../moveit/ompl_interface/model_based_planning_context.h | 4 ++-- .../include/moveit/ompl_interface/ompl_interface.h | 4 ++-- .../joint_space/constrained_planning_state_space.h | 4 ++-- .../joint_space/constrained_planning_state_space_factory.h | 4 ++-- .../parameterization/joint_space/joint_model_state_space.h | 4 ++-- .../joint_space/joint_model_state_space_factory.h | 4 ++-- .../parameterization/model_based_state_space.h | 4 ++-- .../parameterization/model_based_state_space_factory.h | 4 ++-- .../parameterization/work_space/pose_model_state_space.h | 4 ++-- .../work_space/pose_model_state_space_factory.h | 4 ++-- .../include/moveit/ompl_interface/planning_context_manager.h | 4 ++-- .../include/joint_limits_copy/joint_limits.h | 4 ++-- .../include/joint_limits_copy/joint_limits_rosparam.h | 4 ++-- .../pilz_industrial_motion_planner/capability_names.h | 4 ++-- .../pilz_industrial_motion_planner/cartesian_trajectory.h | 4 ++-- .../cartesian_trajectory_point.h | 4 ++-- .../pilz_industrial_motion_planner/command_list_manager.h | 4 ++-- .../pilz_industrial_motion_planner/joint_limits_aggregator.h | 4 ++-- .../pilz_industrial_motion_planner/joint_limits_container.h | 4 ++-- .../pilz_industrial_motion_planner/joint_limits_extension.h | 4 ++-- .../joint_limits_interface_extension.h | 4 ++-- .../pilz_industrial_motion_planner/joint_limits_validator.h | 4 ++-- .../pilz_industrial_motion_planner/limits_container.h | 4 ++-- .../move_group_sequence_action.h | 4 ++-- .../move_group_sequence_service.h | 4 ++-- .../pilz_industrial_motion_planner/path_circle_generator.h | 4 ++-- .../pilz_industrial_motion_planner.h | 4 ++-- .../pilz_industrial_motion_planner/plan_components_builder.h | 4 ++-- .../pilz_industrial_motion_planner/planning_context_base.h | 4 ++-- .../pilz_industrial_motion_planner/planning_context_circ.h | 4 ++-- .../pilz_industrial_motion_planner/planning_context_lin.h | 4 ++-- .../pilz_industrial_motion_planner/planning_context_loader.h | 4 ++-- .../planning_context_loader_circ.h | 4 ++-- .../planning_context_loader_lin.h | 4 ++-- .../planning_context_loader_ptp.h | 4 ++-- .../pilz_industrial_motion_planner/planning_context_ptp.h | 4 ++-- .../pilz_industrial_motion_planner/planning_exceptions.h | 4 ++-- .../pilz_industrial_motion_planner/tip_frame_getter.h | 4 ++-- .../trajectory_blend_request.h | 4 ++-- .../trajectory_blend_response.h | 4 ++-- .../pilz_industrial_motion_planner/trajectory_blender.h | 4 ++-- .../trajectory_blender_transition_window.h | 4 ++-- .../pilz_industrial_motion_planner/trajectory_functions.h | 4 ++-- .../trajectory_generation_exceptions.h | 4 ++-- .../pilz_industrial_motion_planner/trajectory_generator.h | 4 ++-- .../trajectory_generator_circ.h | 4 ++-- .../trajectory_generator_lin.h | 4 ++-- .../trajectory_generator_ptp.h | 4 ++-- .../pilz_industrial_motion_planner/velocity_profile_atrap.h | 4 ++-- .../pilz_industrial_motion_planner_testutils/async_test.h | 4 ++-- .../pilz_industrial_motion_planner_testutils/basecmd.h | 4 ++-- .../cartesianconfiguration.h | 4 ++-- .../cartesianpathconstraintsbuilder.h | 4 ++-- .../pilz_industrial_motion_planner_testutils/center.h | 4 ++-- .../pilz_industrial_motion_planner_testutils/checks.h | 4 ++-- .../include/pilz_industrial_motion_planner_testutils/circ.h | 4 ++-- .../circ_auxiliary_types.h | 4 ++-- .../pilz_industrial_motion_planner_testutils/circauxiliary.h | 4 ++-- .../command_types_typedef.h | 4 ++-- .../default_values.h | 4 ++-- .../exception_types.h | 4 ++-- .../goalconstraintsmsgconvertible.h | 4 ++-- .../pilz_industrial_motion_planner_testutils/gripper.h | 4 ++-- .../pilz_industrial_motion_planner_testutils/interim.h | 4 ++-- .../jointconfiguration.h | 4 ++-- .../include/pilz_industrial_motion_planner_testutils/lin.h | 4 ++-- .../pilz_industrial_motion_planner_testutils/motioncmd.h | 4 ++-- .../motionplanrequestconvertible.h | 4 ++-- .../include/pilz_industrial_motion_planner_testutils/ptp.h | 4 ++-- .../robotconfiguration.h | 4 ++-- .../robotstatemsgconvertible.h | 4 ++-- .../pilz_industrial_motion_planner_testutils/sequence.h | 4 ++-- .../testdata_loader.h | 4 ++-- .../pilz_industrial_motion_planner_testutils/xml_constants.h | 4 ++-- .../xml_testdata_loader.h | 4 ++-- .../stomp/include/stomp_moveit/conversion_functions.h | 4 ++-- moveit_planners/stomp/include/stomp_moveit/cost_functions.h | 4 ++-- .../stomp/include/stomp_moveit/filter_functions.h | 4 ++-- .../stomp/include/stomp_moveit/math/multivariate_gaussian.h | 4 ++-- .../stomp/include/stomp_moveit/noise_generators.h | 4 ++-- .../include/stomp_moveit/stomp_moveit_planning_context.h | 4 ++-- .../stomp/include/stomp_moveit/stomp_moveit_task.h | 4 ++-- .../stomp/include/stomp_moveit/trajectory_visualization.h | 4 ++-- .../include/moveit_ros_control_interface/ControllerHandle.h | 4 ++-- .../action_based_controller_handle.h | 4 ++-- .../empty_controller_handle.h | 4 ++-- .../follow_joint_trajectory_controller_handle.h | 4 ++-- .../gripper_controller_handle.h | 4 ++-- .../include/moveit_py/moveit_py_utils/copy_ros_msg.h | 4 ++-- .../include/moveit_py/moveit_py_utils/ros_msg_typecasters.h | 4 ++-- .../benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h | 4 ++-- .../benchmarks/include/moveit/benchmarks/BenchmarkOptions.h | 4 ++-- .../include/moveit/global_planner/global_planner_component.h | 4 ++-- .../include/moveit/global_planner/global_planner_interface.h | 4 ++-- .../include/moveit/global_planner/moveit_planning_pipeline.h | 4 ++-- .../moveit/hybrid_planning_manager/hybrid_planning_events.h | 4 ++-- .../moveit/hybrid_planning_manager/hybrid_planning_manager.h | 4 ++-- .../moveit/hybrid_planning_manager/planner_logic_interface.h | 4 ++-- .../planner_logic_plugins/replan_invalidated_trajectory.h | 4 ++-- .../moveit/planner_logic_plugins/single_plan_execution.h | 4 ++-- .../local_constraint_solver_plugins/forward_trajectory.h | 4 ++-- .../include/moveit/local_planner/feedback_types.h | 4 ++-- .../moveit/local_planner/local_constraint_solver_interface.h | 4 ++-- .../include/moveit/local_planner/local_planner_component.h | 4 ++-- .../moveit/local_planner/trajectory_operator_interface.h | 4 ++-- .../moveit/trajectory_operator_plugins/simple_sampler.h | 4 ++-- .../move_group/include/moveit/move_group/capability_names.h | 4 ++-- .../include/moveit/move_group/move_group_capability.h | 4 ++-- .../include/moveit/move_group/move_group_context.h | 4 ++-- .../moveit_servo/include/moveit_servo/collision_monitor.h | 4 ++-- moveit_ros/moveit_servo/include/moveit_servo/servo.h | 4 ++-- moveit_ros/moveit_servo/include/moveit_servo/servo_node.h | 4 ++-- moveit_ros/moveit_servo/include/moveit_servo/utils/command.h | 4 ++-- moveit_ros/moveit_servo/include/moveit_servo/utils/common.h | 4 ++-- .../moveit_servo/include/moveit_servo/utils/datatypes.h | 4 ++-- .../moveit/occupancy_map_monitor/occupancy_map_monitor.h | 4 ++-- .../occupancy_map_monitor_middleware_handle.h | 4 ++-- .../moveit/occupancy_map_monitor/occupancy_map_updater.h | 4 ++-- .../depth_image_octomap_updater.h | 4 ++-- .../moveit/lazy_free_space_updater/lazy_free_space_updater.h | 4 ++-- .../include/moveit/mesh_filter/depth_self_filter_nodelet.h | 4 ++-- .../mesh_filter/include/moveit/mesh_filter/filter_job.h | 4 ++-- .../mesh_filter/include/moveit/mesh_filter/gl_mesh.h | 4 ++-- .../mesh_filter/include/moveit/mesh_filter/gl_renderer.h | 4 ++-- .../mesh_filter/include/moveit/mesh_filter/mesh_filter.h | 4 ++-- .../include/moveit/mesh_filter/mesh_filter_base.h | 4 ++-- .../mesh_filter/include/moveit/mesh_filter/sensor_model.h | 4 ++-- .../include/moveit/mesh_filter/stereo_camera_model.h | 4 ++-- .../include/moveit/mesh_filter/transform_provider.h | 4 ++-- .../include/moveit/point_containment_filter/shape_mask.h | 4 ++-- .../pointcloud_octomap_updater/pointcloud_octomap_updater.h | 4 ++-- .../include/moveit/semantic_world/semantic_world.h | 4 ++-- .../moveit/collision_plugin_loader/collision_plugin_loader.h | 4 ++-- .../constraint_sampler_manager_loader.h | 4 ++-- .../kinematics_plugin_loader/kinematics_plugin_loader.h | 4 ++-- .../moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h | 4 ++-- .../include/moveit/moveit_cpp/planning_component.h | 4 ++-- .../include/moveit/plan_execution/plan_execution.h | 4 ++-- .../include/moveit/plan_execution/plan_representation.h | 4 ++-- .../include/moveit/planning_pipeline/planning_pipeline.h | 4 ++-- .../planning_pipeline_interfaces/plan_responses_container.h | 4 ++-- .../planning_pipeline_interfaces.h | 4 ++-- .../solution_selection_functions.h | 4 ++-- .../stopping_criterion_functions.h | 4 ++-- .../moveit/planning_scene_monitor/current_state_monitor.h | 4 ++-- .../current_state_monitor_middleware_handle.h | 4 ++-- .../moveit/planning_scene_monitor/planning_scene_monitor.h | 4 ++-- .../moveit/planning_scene_monitor/trajectory_monitor.h | 4 ++-- .../trajectory_monitor_middleware_handle.h | 4 ++-- .../rdf_loader/include/moveit/rdf_loader/rdf_loader.h | 4 ++-- .../moveit/rdf_loader/synchronized_string_parameter.h | 4 ++-- .../include/moveit/robot_model_loader/robot_model_loader.h | 4 ++-- .../trajectory_execution_manager.h | 4 ++-- .../common_planning_interface_objects/common_objects.h | 4 ++-- .../moveit/move_group_interface/move_group_interface.h | 4 ++-- .../planning_scene_interface/planning_scene_interface.h | 4 ++-- .../include/moveit/robot_interaction/interaction.h | 4 ++-- .../include/moveit/robot_interaction/interaction_handler.h | 4 ++-- .../moveit/robot_interaction/interactive_marker_helpers.h | 4 ++-- .../include/moveit/robot_interaction/kinematic_options.h | 4 ++-- .../include/moveit/robot_interaction/kinematic_options_map.h | 4 ++-- .../include/moveit/robot_interaction/locked_robot_state.h | 4 ++-- .../include/moveit/robot_interaction/robot_interaction.h | 4 ++-- moveit_ros/tests/include/parameter_name_list.h | 5 ++--- .../include/moveit/trajectory_cache/trajectory_cache.h | 4 ++-- .../motion_planning_rviz_plugin/interactive_marker_display.h | 4 ++-- .../motion_planning_rviz_plugin/motion_planning_display.h | 4 ++-- .../motion_planning_rviz_plugin/motion_planning_frame.h | 4 ++-- .../motion_planning_frame_joints_widget.h | 4 ++-- .../motion_planning_param_widget.h | 4 ++-- .../planning_scene_rviz_plugin/background_processing.h | 4 ++-- .../planning_scene_rviz_plugin/planning_scene_display.h | 4 ++-- .../moveit/robot_state_rviz_plugin/robot_state_display.h | 4 ++-- .../include/moveit/rviz_plugin_render_tools/octomap_render.h | 4 ++-- .../moveit/rviz_plugin_render_tools/planning_link_updater.h | 4 ++-- .../moveit/rviz_plugin_render_tools/planning_scene_render.h | 4 ++-- .../include/moveit/rviz_plugin_render_tools/render_shapes.h | 4 ++-- .../rviz_plugin_render_tools/robot_state_visualization.h | 4 ++-- .../moveit/rviz_plugin_render_tools/trajectory_panel.h | 4 ++-- .../rviz_plugin_render_tools/trajectory_visualization.h | 4 ++-- .../include/ogre_helpers/mesh_shape.h | 4 ++-- .../moveit/trajectory_rviz_plugin/trajectory_display.h | 4 ++-- .../warehouse/include/moveit/warehouse/constraints_storage.h | 4 ++-- .../include/moveit/warehouse/moveit_message_storage.h | 4 ++-- .../include/moveit/warehouse/planning_scene_storage.h | 4 ++-- .../include/moveit/warehouse/planning_scene_world_storage.h | 4 ++-- .../warehouse/include/moveit/warehouse/state_storage.h | 4 ++-- .../moveit/warehouse/trajectory_constraints_storage.h | 4 ++-- .../warehouse/include/moveit/warehouse/warehouse_connector.h | 4 ++-- .../include/moveit_setup_app_plugins/launch_bundle.h | 4 ++-- .../include/moveit_setup_app_plugins/launches.h | 4 ++-- .../include/moveit_setup_app_plugins/launches_config.h | 4 ++-- .../include/moveit_setup_app_plugins/launches_widget.h | 4 ++-- .../include/moveit_setup_app_plugins/perception.h | 4 ++-- .../include/moveit_setup_app_plugins/perception_config.h | 4 ++-- .../include/moveit_setup_app_plugins/perception_widget.h | 4 ++-- .../include/moveit_setup_assistant/navigation_widget.h | 4 ++-- .../include/moveit_setup_assistant/setup_assistant_widget.h | 4 ++-- .../include/moveit_setup_controllers/control_xacro_config.h | 4 ++-- .../moveit_setup_controllers/controller_edit_widget.h | 4 ++-- .../include/moveit_setup_controllers/controllers.h | 4 ++-- .../include/moveit_setup_controllers/controllers_config.h | 4 ++-- .../include/moveit_setup_controllers/controllers_widget.h | 4 ++-- .../include/moveit_setup_controllers/included_xacro_config.h | 4 ++-- .../include/moveit_setup_controllers/modified_urdf_config.h | 4 ++-- .../include/moveit_setup_controllers/moveit_controllers.h | 4 ++-- .../moveit_setup_controllers/moveit_controllers_config.h | 4 ++-- .../include/moveit_setup_controllers/ros2_controllers.h | 4 ++-- .../moveit_setup_controllers/ros2_controllers_config.h | 4 ++-- .../include/moveit_setup_controllers/urdf_modifications.h | 4 ++-- .../moveit_setup_controllers/urdf_modifications_widget.h | 4 ++-- .../include/moveit_setup_core_plugins/author_information.h | 4 ++-- .../moveit_setup_core_plugins/author_information_widget.h | 4 ++-- .../include/moveit_setup_core_plugins/configuration_files.h | 4 ++-- .../moveit_setup_core_plugins/configuration_files_widget.h | 4 ++-- .../include/moveit_setup_core_plugins/start_screen.h | 4 ++-- .../include/moveit_setup_core_plugins/start_screen_widget.h | 4 ++-- .../include/moveit_setup_framework/config.h | 4 ++-- .../moveit_setup_framework/data/package_settings_config.h | 4 ++-- .../include/moveit_setup_framework/data/srdf_config.h | 4 ++-- .../include/moveit_setup_framework/data/urdf_config.h | 4 ++-- .../include/moveit_setup_framework/data_warehouse.h | 4 ++-- .../include/moveit_setup_framework/generated_file.h | 4 ++-- .../include/moveit_setup_framework/generated_time.h | 4 ++-- .../include/moveit_setup_framework/qt/double_list_widget.h | 4 ++-- .../include/moveit_setup_framework/qt/helper_widgets.h | 4 ++-- .../include/moveit_setup_framework/qt/rviz_panel.h | 4 ++-- .../include/moveit_setup_framework/qt/setup_step_widget.h | 4 ++-- .../moveit_setup_framework/qt/xml_syntax_highlighter.h | 4 ++-- .../include/moveit_setup_framework/setup_step.h | 4 ++-- .../include/moveit_setup_framework/templates.h | 4 ++-- .../include/moveit_setup_framework/testing_utils.h | 4 ++-- .../include/moveit_setup_framework/utilities.h | 4 ++-- .../include/moveit_setup_simulation/simulation.h | 4 ++-- .../include/moveit_setup_simulation/simulation_widget.h | 4 ++-- .../moveit_setup_srdf_plugins/collision_linear_model.h | 4 ++-- .../moveit_setup_srdf_plugins/collision_matrix_model.h | 4 ++-- .../moveit_setup_srdf_plugins/compute_default_collisions.h | 4 ++-- .../include/moveit_setup_srdf_plugins/default_collisions.h | 4 ++-- .../moveit_setup_srdf_plugins/default_collisions_widget.h | 4 ++-- .../include/moveit_setup_srdf_plugins/end_effectors.h | 4 ++-- .../include/moveit_setup_srdf_plugins/end_effectors_widget.h | 4 ++-- .../include/moveit_setup_srdf_plugins/group_edit_widget.h | 4 ++-- .../include/moveit_setup_srdf_plugins/group_meta_config.h | 4 ++-- .../moveit_setup_srdf_plugins/kinematic_chain_widget.h | 4 ++-- .../include/moveit_setup_srdf_plugins/passive_joints.h | 4 ++-- .../moveit_setup_srdf_plugins/passive_joints_widget.h | 4 ++-- .../include/moveit_setup_srdf_plugins/planning_groups.h | 4 ++-- .../moveit_setup_srdf_plugins/planning_groups_widget.h | 4 ++-- .../include/moveit_setup_srdf_plugins/robot_poses.h | 4 ++-- .../include/moveit_setup_srdf_plugins/robot_poses_widget.h | 4 ++-- .../include/moveit_setup_srdf_plugins/rotated_header_view.h | 4 ++-- .../include/moveit_setup_srdf_plugins/srdf_step.h | 4 ++-- .../include/moveit_setup_srdf_plugins/virtual_joints.h | 4 ++-- .../moveit_setup_srdf_plugins/virtual_joints_widget.h | 4 ++-- 376 files changed, 752 insertions(+), 753 deletions(-) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h index 55a5c952ec..f947e9f0cc 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h index a654b1fcd8..178bf77d66 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h index 917d1ffc33..8880966f60 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h index 1ea509f5ef..224c49bb9c 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h index ccaa7a0266..77f9d45120 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h index cafe073768..39cae0f308 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h index 3b86b18a8b..5a1f30343b 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h index d61b489143..57e8da8a8d 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h index 3a58b2cdf8..241f4c017d 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h index ff191d6790..9f5fedb060 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h b/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h index fd6c332bf9..8ff270cca7 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h index ebc6065d1b..c34a810726 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h index 9003a65db9..5609dd09e2 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/world.h b/moveit_core/collision_detection/include/moveit/collision_detection/world.h index c4eb520017..bb82985627 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/world.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/world.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h b/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h index 31c28b2314..2935f0ee89 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h index 6c0c80c472..6cebcf63a8 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (Apache License) @@ -24,4 +24,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h index 5a33c73dce..7fb8b16ae4 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD-2-Clause) @@ -37,4 +37,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h index 177c093e6e..3afb39f0a5 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD-2-Clause) @@ -37,4 +37,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h index be6f9c099e..24897d1d68 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD-2-Clause) @@ -37,4 +37,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h index 4ccf8f2152..72d3579bf7 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD-2-Clause) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h index c429afe85f..150c7b92dd 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (Apache License) @@ -24,4 +24,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h index ccacba24d1..d1d6f17cc6 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (Apache License) @@ -24,4 +24,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h index 2e09d55218..1a381cfef0 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h index 3ad7034b0d..df1db499fa 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h index 9920a297d1..afe53ee15f 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h index 2356c90c28..6511f712ce 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h index dd64c6aa51..a99ad8a198 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h index 02d98db6fb..9a107a3074 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h index bb2c4cf3d3..ff6cd9eb15 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h index 4b866aec57..5ac09571d1 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h index b557944298..5dab2cb444 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h index e2c906ca33..4929f799c1 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h index 655f7929d4..1b53935513 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h index 836346946c..f2a160878f 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h index 88f8c90e03..7c9457b887 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h index d631d928d5..67abbd33c2 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h index 773e5334b5..d570465094 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h index 0b39d90619..ba8cf6014d 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h index 331d2ce681..cab5b3a53a 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h index 5858f85871..e440f534d3 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h index 157e7e8ade..82f4603be6 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h index 748a17ae36..bb3d9d33b7 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h b/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h index 4be0a25300..760570e526 100644 --- a/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h +++ b/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/distance_field/include/moveit/distance_field/distance_field.h b/moveit_core/distance_field/include/moveit/distance_field/distance_field.h index bc69c4e59b..5409c64695 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/distance_field.h +++ b/moveit_core/distance_field/include/moveit/distance_field/distance_field.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h b/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h index e6a0596ea4..1ede20f322 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h +++ b/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h b/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h index 0aa607546b..aaa0e6cd14 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h +++ b/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h b/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h index f671057f29..82c5bc37ac 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h +++ b/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h b/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h index 24459297e9..84bd3f6a59 100644 --- a/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h +++ b/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/exceptions/include/moveit/exceptions/exceptions.h b/moveit_core/exceptions/include/moveit/exceptions/exceptions.h index 7b7de5bc08..f2b561eb36 100644 --- a/moveit_core/exceptions/include/moveit/exceptions/exceptions.h +++ b/moveit_core/exceptions/include/moveit/exceptions/exceptions.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h index 8a1088c414..dda518de8a 100644 --- a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h +++ b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h index 192067fc81..638d456339 100644 --- a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h +++ b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h index 6ad801d8ae..ba8eba1cdf 100644 --- a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h +++ b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h b/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h index 6022c150f6..69fd46a315 100644 --- a/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h +++ b/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/macros/include/moveit/macros/class_forward.h b/moveit_core/macros/include/moveit/macros/class_forward.h index 861cfd90bb..5a5deeedb3 100644 --- a/moveit_core/macros/include/moveit/macros/class_forward.h +++ b/moveit_core/macros/include/moveit/macros/class_forward.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/macros/include/moveit/macros/console_colors.h b/moveit_core/macros/include/moveit/macros/console_colors.h index 88cb4d0a3a..598ebe97e3 100644 --- a/moveit_core/macros/include/moveit/macros/console_colors.h +++ b/moveit_core/macros/include/moveit/macros/console_colors.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/macros/include/moveit/macros/declare_ptr.h b/moveit_core/macros/include/moveit/macros/declare_ptr.h index 32fc0be8be..559df2c011 100644 --- a/moveit_core/macros/include/moveit/macros/declare_ptr.h +++ b/moveit_core/macros/include/moveit/macros/declare_ptr.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/macros/include/moveit/macros/deprecation.h b/moveit_core/macros/include/moveit/macros/deprecation.h index cc4aea3ae5..122ddb8114 100644 --- a/moveit_core/macros/include/moveit/macros/deprecation.h +++ b/moveit_core/macros/include/moveit/macros/deprecation.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h index 50bb6569f8..7c017835e0 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -76,4 +76,4 @@ c --------x--- v | #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h index 794aaeef77..b5c1daa322 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -43,4 +43,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h index 70e3311fc7..fb3821e735 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -42,4 +42,4 @@ Description: Applies jerk/acceleration/velocity limits to online motion commands #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h index ff8c44a743..f7c69a7cca 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -42,4 +42,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h index 3467b25339..7793132fcb 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h index 48a6830e35..01437b9dca 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h index cd33af62a0..d0762020a2 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -42,4 +42,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h index 475ba83946..f28daaa97a 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h index b8d632baf8..565761023a 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h index 34f26636fb..8f44903795 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/robot_model/include/moveit/robot_model/aabb.h b/moveit_core/robot_model/include/moveit/robot_model/aabb.h index a8141857da..86bc4f6efc 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/aabb.h +++ b/moveit_core/robot_model/include/moveit/robot_model/aabb.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h index 6245343815..6f039b94ba 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h index ef0f3cc4e9..26291fd095 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/robot_model/include/moveit/robot_model/joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/joint_model.h index 52bd598f99..35aa6a15c3 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/joint_model.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -41,4 +41,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h index c66b2dc5e0..69643b5292 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h +++ b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -41,4 +41,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/robot_model/include/moveit/robot_model/link_model.h b/moveit_core/robot_model/include/moveit/robot_model/link_model.h index 5737099176..dd0d74a5a6 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/link_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/link_model.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h index cae2778d5d..7cb2dde674 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h index e73f126fac..a49ae38ca4 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h index 1f4386ac44..6fb880325e 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h index 5b85b5fac6..92161465e7 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -41,4 +41,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/robot_state/include/moveit/robot_state/attached_body.h b/moveit_core/robot_state/include/moveit/robot_state/attached_body.h index 8dfe3d9815..a6ea3ae946 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/attached_body.h +++ b/moveit_core/robot_state/include/moveit/robot_state/attached_body.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h b/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h index 9aeb91f1c6..309d850268 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h +++ b/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -42,4 +42,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/robot_state/include/moveit/robot_state/conversions.h b/moveit_core/robot_state/include/moveit/robot_state/conversions.h index d447e36d7b..958016f790 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/conversions.h +++ b/moveit_core/robot_state/include/moveit/robot_state/conversions.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h index f27b2c5405..7c3741893d 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h +++ b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -41,4 +41,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h index a9c1a06c14..961c0db49f 100644 --- a/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h +++ b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h index 82659e4e97..20220875dc 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /******************************************************************************* * BSD 3-Clause License @@ -39,4 +39,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h index 68185fda6b..1e86073e6a 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /* * Copyright (c) 2011-2012, Georgia Tech Research Corporation @@ -42,4 +42,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h index 3515b03f34..7e644e70dd 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h @@ -1,7 +1,7 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py #pragma once #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h index bcbd787f87..3c7c5a6c26 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/transforms/include/moveit/transforms/transforms.h b/moveit_core/transforms/include/moveit/transforms/transforms.h index 98ada1074c..5c88a25cbd 100644 --- a/moveit_core/transforms/include/moveit/transforms/transforms.h +++ b/moveit_core/transforms/include/moveit/transforms/transforms.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/utils/include/moveit/utils/eigen_test_utils.h b/moveit_core/utils/include/moveit/utils/eigen_test_utils.h index 266c39d608..e2b203ea07 100644 --- a/moveit_core/utils/include/moveit/utils/eigen_test_utils.h +++ b/moveit_core/utils/include/moveit/utils/eigen_test_utils.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/utils/include/moveit/utils/lexical_casts.h b/moveit_core/utils/include/moveit/utils/lexical_casts.h index f419f9556a..7c60075c2b 100644 --- a/moveit_core/utils/include/moveit/utils/lexical_casts.h +++ b/moveit_core/utils/include/moveit/utils/lexical_casts.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/utils/include/moveit/utils/logger.h b/moveit_core/utils/include/moveit/utils/logger.h index 337eb5035d..36ec67f29b 100644 --- a/moveit_core/utils/include/moveit/utils/logger.h +++ b/moveit_core/utils/include/moveit/utils/logger.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/utils/include/moveit/utils/message_checks.h b/moveit_core/utils/include/moveit/utils/message_checks.h index 9b2c1742a9..a42fe726ed 100644 --- a/moveit_core/utils/include/moveit/utils/message_checks.h +++ b/moveit_core/utils/include/moveit/utils/message_checks.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/utils/include/moveit/utils/moveit_error_code.h b/moveit_core/utils/include/moveit/utils/moveit_error_code.h index b312644c0c..fd06af4808 100644 --- a/moveit_core/utils/include/moveit/utils/moveit_error_code.h +++ b/moveit_core/utils/include/moveit/utils/moveit_error_code.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/utils/include/moveit/utils/rclcpp_utils.h b/moveit_core/utils/include/moveit/utils/rclcpp_utils.h index e880425af4..c80ec49c27 100644 --- a/moveit_core/utils/include/moveit/utils/rclcpp_utils.h +++ b/moveit_core/utils/include/moveit/utils/rclcpp_utils.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /* * Copyright (C) 2009, Willow Garage, Inc. @@ -31,4 +31,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h b/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h index d8c182983f..0e7c572005 100644 --- a/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h +++ b/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -41,4 +41,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h index 86cb2c4665..2f7509f35e 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h index 0b547c037e..a7345a379e 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h index 3678f08e26..884f9972d8 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -42,4 +42,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h index 9574b89d87..2582f3db00 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -42,4 +42,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h index 977c010cbc..fd81e40bc1 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -42,4 +42,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h index 4ec23bf4a7..7218a0cb11 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h +++ b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py // Copyright (C) 2007 Ruben Smits @@ -29,4 +29,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h index cda4dbaff8..b88ae07e69 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h +++ b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h index c95ad1843b..637c72739e 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h +++ b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h b/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h index ebd067b210..eb26255f5b 100644 --- a/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h +++ b/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -45,4 +45,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h index 639bcdf035..5cac19f060 100644 --- a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h +++ b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h index 75c454d113..f6da1a348b 100644 --- a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h +++ b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h index 6c223fbac6..61f86afd60 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h index 10a07f1252..a7d76da52f 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h index bf6ee51735..72c8edd111 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -43,4 +43,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h index 26872644f2..d037f1449e 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h index 95a35559a9..9c62527caa 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h index 705a3de9e9..22c983ad1a 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h index 3bdb099e23..77a7791205 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h index 7e9f52de86..d3a6d9a9e6 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h index 9cadb32cd3..80b3463f68 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h index dcc8c0c064..59fe5b5b8f 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h index 5c2033387d..1af59ae7cb 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h index 0fea7899c5..8506ba061f 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h index 5ea738a78a..77120f01eb 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h index 31b654086c..d7162e02d2 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h index aafee34856..6177cdb68e 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -51,4 +51,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h index 4ff68592fe..71f27870be 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h index 061e0b57e4..3bba66f6ac 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h index 9f31737398..2c50a0c40a 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h index 233ac0cd71..8672745ceb 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h index 84b63f5089..e175e1bbe9 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -41,4 +41,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h index 86b5291779..f11ee67fcb 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h index cc917bd480..05eed88720 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h index e50596bbc4..3e79a83868 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h index 55791b118c..e157e9826f 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h index 7303005a72..23f4466084 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h index 808935c0f1..ba3cdee5c8 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h index b8023396a9..1840319ad9 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h index 77122127b7..ed02e48a4c 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py // Copyright 2020 PAL Robotics S.L. // @@ -20,4 +20,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h index 19fc8e076b..8393b5c3bd 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py // Copyright 2020 PAL Robotics S.L. // @@ -20,4 +20,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h index 959363cce3..07151242dc 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h index 197d0388ed..f162963b78 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h index 01be7d7d0f..5f7ff9684b 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h index 0d11bf0d3b..4ed08a2a50 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h index e33f3cc8d7..ee948c6e78 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h index dcd3eb1ce8..a6ef5747b2 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h index 0311151f3f..8c5679f0bd 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h index f884727774..66b56fc80d 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h index f580813d58..3ee7e04a43 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h index 9fbd37c1cc..235a547d46 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h index f69562bba8..5905e95ef4 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h index a7b7ba223b..bf28634c9a 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h index ad0092e967..f3ef612240 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h index 258508917b..0a1c4f8d09 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h index c20d8d1d35..ab9616d9c3 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h index 81a68d6f37..6583b46415 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h index 2acce916ab..d8bfc05a0c 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h index d322ee75f1..5a741fd625 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h index 9f79514e75..c409541eda 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h index 5206f7dc39..82b5905e12 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h index e2ea443d87..f753fff0c5 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h index ca1e3da75b..67803c12ac 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h index 30915e99f7..e1297ecb5b 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h index b086348dbd..b57e8de934 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h index 493bf1c7a7..b42792d0b1 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h index f495ea3d7e..9c475d03eb 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h index 62b7632853..3a752f3890 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h index 4339ae01c5..54f924676e 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h index 1fc66b4c91..60c2e69084 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h index f8df0f9c1e..f68c11ba9d 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h index 5005dbd9ef..8b52a07665 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h index 881abff6b5..98e7e6c474 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h index 16ae95b819..c5c80e7d57 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h index 28c87ff119..b6b2f1b5de 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h index 0a50693958..0f7a7c1995 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h index 0ee51b3609..458374f007 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h index 3c792ae663..71b2442dcc 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /* * Copyright (c) 2018 Pilz GmbH & Co. KG @@ -20,4 +20,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h index 532440f973..4b9e6396cb 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h index b7a861800f..d437e18359 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h index a461072e2b..aa1939b311 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h index 7fddb64c69..c8696396ae 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h index aced99e0b9..1c30c39baa 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h index 9d3190f47e..3526cc4d36 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h index 076ff6505b..8dda9ec397 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h index 470ef241bd..6434f3a6d7 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h index 2afffc78ff..337eaa879e 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h index 4e8b975710..b98e9fac33 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h index e28830f2bb..6f7729d705 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h index 4e296b2aec..e8b17f0722 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h index 098cb3fb8e..df970b16e0 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h index 7475244c5e..45c6380b9f 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h index 2d79c288c8..aafabf7f81 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h index 85a909b1ef..d6bca42443 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h index 4c2c9e5d62..1c7d5d8a04 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h index a4c769826e..a29180a2d1 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h index 4a403d0690..01d2d2883d 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h index 07b70266b2..a72867b9a8 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h index 4fcb9f97e1..bcfbe8b18c 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h index eed0a0e0ba..bcd39c48ec 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h index 1f5a941f50..e116a5c43a 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h index 7acd682675..b7df94a4f8 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h index c2bc798b77..0b8ebfd9f5 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h b/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h index 9192be8134..0098ef57cb 100644 --- a/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h +++ b/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -43,4 +43,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/stomp/include/stomp_moveit/cost_functions.h b/moveit_planners/stomp/include/stomp_moveit/cost_functions.h index 0e182d0d4a..3c1988f56d 100644 --- a/moveit_planners/stomp/include/stomp_moveit/cost_functions.h +++ b/moveit_planners/stomp/include/stomp_moveit/cost_functions.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -43,4 +43,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/stomp/include/stomp_moveit/filter_functions.h b/moveit_planners/stomp/include/stomp_moveit/filter_functions.h index 485de47e98..384383e8b9 100644 --- a/moveit_planners/stomp/include/stomp_moveit/filter_functions.h +++ b/moveit_planners/stomp/include/stomp_moveit/filter_functions.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -43,4 +43,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h b/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h index a70d87409c..c241d73e1d 100644 --- a/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h +++ b/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -43,4 +43,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/stomp/include/stomp_moveit/noise_generators.h b/moveit_planners/stomp/include/stomp_moveit/noise_generators.h index 2c953203a9..c0104549fc 100644 --- a/moveit_planners/stomp/include/stomp_moveit/noise_generators.h +++ b/moveit_planners/stomp/include/stomp_moveit/noise_generators.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -43,4 +43,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h index 00f559eacb..cd2ee4254b 100644 --- a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h +++ b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -43,4 +43,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h index 96e98ee12e..9809902ec9 100644 --- a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h +++ b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -58,4 +58,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h b/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h index c68121c58a..4c0b5874b8 100644 --- a/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h +++ b/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -43,4 +43,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h b/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h index 60e76e6dcd..44101e7fe7 100644 --- a/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h +++ b/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h index b353f949ea..78f11dd7ca 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -41,4 +41,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h index ee6603db3c..5ba70c2d14 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h index c01770de36..8747396438 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -41,4 +41,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h index dc0eb46942..867c0b98d3 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -41,4 +41,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h index 4bcab94d93..0e7f2561dd 100644 --- a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h +++ b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h index 669fdb62b5..0fdaef0172 100644 --- a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h +++ b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h index 1ec82739a5..0e361b8079 100644 --- a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h +++ b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h index abf731ece0..9b540f0445 100644 --- a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h +++ b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h index b2754cdd5e..4c9fce2be8 100644 --- a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h +++ b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -42,4 +42,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h index 494719293a..34fe430220 100644 --- a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h +++ b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -43,4 +43,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h b/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h index fa6bfaca11..2337137570 100644 --- a/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h +++ b/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -41,4 +41,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h index 83d623d4cf..98e4235220 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -41,4 +41,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h index 7b713b35c0..8732bfd685 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -42,4 +42,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h index 62dfb347da..33be18b690 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -42,4 +42,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h index b64dc4f8a6..14c62e273d 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -44,4 +44,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h index 92b007c1b1..24f07f848b 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -43,4 +43,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h b/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h index 67d51f012d..568e68a914 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h +++ b/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -44,4 +44,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h index f023001145..a7bce77b87 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -43,4 +43,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h index 8f82285f8d..8682c129bb 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -42,4 +42,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h index fe6a9dccef..01a6acb893 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -43,4 +43,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h index 741a88d6c2..f325f59993 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -42,4 +42,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h b/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h index cc97cdf24f..cbbfff6080 100644 --- a/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h +++ b/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -44,4 +44,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/move_group/include/moveit/move_group/capability_names.h b/moveit_ros/move_group/include/moveit/move_group/capability_names.h index 020b349fe9..3674dfd67d 100644 --- a/moveit_ros/move_group/include/moveit/move_group/capability_names.h +++ b/moveit_ros/move_group/include/moveit/move_group/capability_names.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h b/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h index d1dab0ab87..1e8a719d90 100644 --- a/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h +++ b/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/move_group/include/moveit/move_group/move_group_context.h b/moveit_ros/move_group/include/moveit/move_group/move_group_context.h index cdf9a1c161..8719332728 100644 --- a/moveit_ros/move_group/include/moveit/move_group/move_group_context.h +++ b/moveit_ros/move_group/include/moveit/move_group/move_group_context.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h b/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h index 0d42d8e946..4a8d2a9d5a 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /******************************************************************************* * BSD 3-Clause License @@ -45,4 +45,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/servo.h b/moveit_ros/moveit_servo/include/moveit_servo/servo.h index 730570ccbb..ad86c54637 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/servo.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/servo.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /******************************************************************************* * BSD 3-Clause License @@ -45,4 +45,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h b/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h index f0beef145b..474a259453 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /******************************************************************************* * BSD 3-Clause License @@ -45,4 +45,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h b/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h index e79623a3cb..af75e56f7c 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /******************************************************************************* * BSD 3-Clause License @@ -45,4 +45,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h b/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h index dfbae7c03a..d83cd75517 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /******************************************************************************* * BSD 3-Clause License @@ -45,4 +45,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h b/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h index f9896e5020..aa21b302ed 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /******************************************************************************* * BSD 3-Clause License @@ -45,4 +45,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h index 7e451498ee..cc74d16746 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h index c85f95e170..1df426fcb4 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h index d0037c7434..f41a834775 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h b/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h index 03ee2c13f4..43dfa59d58 100644 --- a/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h +++ b/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h b/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h index cf97b37edd..87828d1674 100644 --- a/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h +++ b/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h index d0ec48091c..6934c7f0ae 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h index 8c8af8af6c..01b50ef7b1 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h index 651291530b..02de95c7e9 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h index 745bf521b9..8832e874f5 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h index 392c0406c6..aa64e21c4e 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h index 9def272c3d..af27294caf 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h index ee9242bfd0..ec8ac0b1df 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h index 067ea22553..58a5f4ef53 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h index 1ef6d2607b..b00a502882 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h b/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h index affa78a63f..b8a32e7d50 100644 --- a/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h +++ b/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h b/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h index e1e6e0aa74..2d51dea8a7 100644 --- a/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h +++ b/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h index da53fdf2a7..6a59bacb08 100644 --- a/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h +++ b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h b/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h index 83fca003d6..48b28df3dd 100644 --- a/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h +++ b/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h b/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h index 098e210e94..d1c37111cb 100644 --- a/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h +++ b/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h b/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h index 2d5163ca79..fe9d9d8ef4 100644 --- a/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h +++ b/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h index d531f1a1aa..74a6efd12c 100644 --- a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h +++ b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -43,4 +43,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h index 385604182d..82c99aa655 100644 --- a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h +++ b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -41,4 +41,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h index dca5dfad5f..a9f111687c 100644 --- a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h +++ b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h index 36538d338b..209cae31b5 100644 --- a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h +++ b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h index c24d9f9f51..afc72fb212 100644 --- a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h +++ b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -43,4 +43,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h index 449da27c26..7c18b123e1 100644 --- a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -41,4 +41,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h index 6b47385bc7..04bef95ac5 100644 --- a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -41,4 +41,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h index fbd1ae637d..66baa7236f 100644 --- a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -41,4 +41,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h index 17553d4b54..1524500528 100644 --- a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -41,4 +41,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h index 57a934f6f7..4cfe88100b 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h index 144ab44929..d18a6e4ad6 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h index d5b1b30187..c968bc632e 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h index 301cc55cea..39c2e6aa63 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h index 70a937d801..0792db4e34 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h index 23173dd5c0..4bef512b1d 100644 --- a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h +++ b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h index 74d375e661..811c39f9ac 100644 --- a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h +++ b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h b/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h index b4ca0a94c9..ba8b028043 100644 --- a/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h +++ b/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h index e152c2f995..4155e62d50 100644 --- a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h +++ b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h b/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h index 1be2600088..f3612f2133 100644 --- a/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h +++ b/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h index 59b3c6a9ef..c55597400f 100644 --- a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h +++ b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -41,4 +41,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h b/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h index 3cf28a748c..330269b521 100644 --- a/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h +++ b/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h index a2400a12a0..ea4815f092 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h index 5f830e4558..392886b4cf 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h index 32500010c8..4e5528fb47 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h index 7034b604f7..ed4cf0f624 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h index d7ed065d6e..c9d0ee92de 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h index 5eeb5b0909..c5812b38e6 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -41,4 +41,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h index a004d717b2..c0992df00d 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/tests/include/parameter_name_list.h b/moveit_ros/tests/include/parameter_name_list.h index a07e682049..aa065e0e12 100644 --- a/moveit_ros/tests/include/parameter_name_list.h +++ b/moveit_ros/tests/include/parameter_name_list.h @@ -1,5 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py - +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -43,4 +42,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h b/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h index 1afa9736a5..3c193ab515 100644 --- a/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h +++ b/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py // Copyright 2024 Intrinsic Innovation LLC. // @@ -23,4 +23,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h index 119e152141..127b36803d 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /* * Copyright (c) 2008, Willow Garage, Inc. @@ -39,4 +39,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h index b768d91b93..59df71ad3c 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h index d7642070ac..1d5ba0c1d2 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h index 572b1cbdda..3c4adab291 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h index 4ab18f0bd1..761e2b3d3f 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h index 0d336bd172..63dd61ffa3 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h index 3aaa591487..a1e5b39f99 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h b/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h index f69005ec71..897a8a6eca 100644 --- a/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h +++ b/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h index 944fa57a7d..d966a246de 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h index f6d8a754c7..1316751d95 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h index e3f34928c8..8624e942de 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h index 6b11519597..0ce814312c 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h index c3ba555b9e..0adc7ab31d 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h index cff0f4a4ed..feb1400e4b 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h index 1366ae7054..a542878632 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h index c2fedc2bcc..40aab1a5d6 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /* * Copyright (c) 2008, Willow Garage, Inc. @@ -33,4 +33,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h b/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h index bb983d620b..34d1101690 100644 --- a/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h +++ b/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -42,4 +42,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h index 0d992cdf91..577ab40a49 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h index c07a736278..f12b9edecf 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h index dc9101f881..f7a5584261 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h index 32dd86efd9..b06ebb699b 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h index 21845f13fc..d3946532f5 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h index 92064644e2..41061f7cbf 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h b/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h index 5d2ab6ab7f..825175e9de 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h index 0a90012a9e..2e43b89db2 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -39,4 +39,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h index 819fe74b74..366beb853c 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -39,4 +39,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h index 7f513d7c44..38342c56dd 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -39,4 +39,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h index f9e7e70a04..eb3f96db93 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -39,4 +39,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h index ec9fc89d4f..ef345878e2 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -39,4 +39,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h index ae8dba7e22..98eee2283d 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -39,4 +39,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h index 6790825398..ac83baedbd 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -39,4 +39,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h index c35197d581..45f878256d 100644 --- a/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h +++ b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h index c15a6f0208..24ff1576b7 100644 --- a/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h +++ b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h index 4f5b473cdb..0bb89549e9 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h index 16a637cffc..f62776370c 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -39,4 +39,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h index ecc4d74d94..c554d9b5ed 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -39,4 +39,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h index ffe3f0efb7..6398bbb91a 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -39,4 +39,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h index c6904e12be..8ca21f75d6 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -39,4 +39,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h index e0198f8711..84177205da 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h index d785dcd0fb..1df30c1d49 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h index 7973ed5fa5..fb1d3d413b 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h index 9b6016c32f..1196bb1223 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h index 97bb0fef75..5c6a5a7364 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h index 272099d1c8..e473047b50 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h index 888dd2a3c3..d5eb9ff70a 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -39,4 +39,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h index e29e86716e..62169b1846 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h index b3c8ae4adb..46ad9305ec 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -39,4 +39,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h index ea3f582823..75df4663e6 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h index 57dea204e6..69adfd0b1c 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h index 8e380c5bdb..f2bdde815e 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h index 18ddd400e1..4615293d29 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h index 07516d35aa..c53da02446 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h index 1f783c1078..390a96073b 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h index b68405df3a..3c11ad1929 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h index 00c14f1242..c24a63ed8e 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -39,4 +39,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h index 12b8dc83ac..393e276630 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -38,4 +38,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h index f245c04234..d50fe55346 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -46,4 +46,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h index 2340d51176..c9a5db012a 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h index 48e0195235..6ec71b3a2a 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h index 6bf4d21261..4fa521fb68 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h index 1a3e3957da..ae90d03442 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h index 17e38b27a2..582cc68831 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h index 0bdbe083e9..e71ef399c6 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h index f323cfaabf..4a8a0b1388 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h index 5bc90726e7..5e921d3e33 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h index 41a2b80d3e..950e91556b 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -39,4 +39,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h index 9cbec2d37c..4c5c1eb807 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h index 8aff3d4627..81d44828b2 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h index 4d1ff8dde8..3b882053d0 100644 --- a/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h +++ b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -39,4 +39,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h index d1a6e08bf5..b353e3b699 100644 --- a/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h +++ b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -39,4 +39,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h index 01088c4108..db7b396e57 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h index 0389fdcda4..875df207e4 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h index 6b30d39d8d..e0ff4457c0 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h index ccb3c9bd92..823b6cc5c8 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -39,4 +39,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h index cbed5d9f5d..8da3914fb1 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h index d79cd30ff4..0dc085d556 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -39,4 +39,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h index 3b5139e69a..d0d3998039 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h index e15d52b9f0..b8ce516ad6 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h index 51d73589e7..fdf4de54e2 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -39,4 +39,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h index ba8ec5ae06..6f44c9eda1 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h index 82d916279d..b91f86e5cc 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -39,4 +39,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h index 1bcceba81e..0b4669b21a 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h index 57c6a260e0..51f179cbcf 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -39,4 +39,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h index 191a88b4cc..cd6d2d4cf7 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h index 947fcc4204..6a2621c9c4 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -39,4 +39,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h index 7b4f8055ff..a4edfe5f2a 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h index 4700d6c9c8..1a980fdc5d 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h index b40885060d..dd7daea414 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -39,4 +39,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h index e49a70b6b2..3a2097394c 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -39,4 +39,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h index 30928bbc3c..d5f8fdfd65 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/create_deprecated_headers.py +This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) @@ -40,4 +40,4 @@ This file was autogenerated by /root/ws_moveit/src/moveit2/./moveit/scripts/crea #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include From b4a6299ed2bfe48b2bd98817ef9e57cb458fde6a Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Thu, 21 Nov 2024 18:12:57 +0000 Subject: [PATCH 40/53] Deletes referenced to now removed cmake file --- moveit_common/moveit_common-extras.cmake | 1 - 1 file changed, 1 deletion(-) diff --git a/moveit_common/moveit_common-extras.cmake b/moveit_common/moveit_common-extras.cmake index e844c0cbc2..08e01eb31b 100644 --- a/moveit_common/moveit_common-extras.cmake +++ b/moveit_common/moveit_common-extras.cmake @@ -26,4 +26,3 @@ # OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. include("${moveit_common_DIR}/moveit_package.cmake") -include("${moveit_common_DIR}/deprecated_headers.cmake") From aca9ab1ba729b71b905fe225da764c58e8c87bc8 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Thu, 21 Nov 2024 18:23:35 +0000 Subject: [PATCH 41/53] Minor tweaks to script and updates .h files --- moveit/scripts/create_deprecated_headers.py | 4 ++-- .../allvalid/collision_detector_allocator_allvalid.h | 2 +- .../collision_detection/allvalid/collision_env_allvalid.h | 2 +- .../include/moveit/collision_detection/collision_common.h | 2 +- .../moveit/collision_detection/collision_detector_allocator.h | 2 +- .../include/moveit/collision_detection/collision_env.h | 2 +- .../include/moveit/collision_detection/collision_matrix.h | 2 +- .../moveit/collision_detection/collision_octomap_filter.h | 2 +- .../include/moveit/collision_detection/collision_plugin.h | 2 +- .../moveit/collision_detection/collision_plugin_cache.h | 2 +- .../include/moveit/collision_detection/collision_tools.h | 2 +- .../include/moveit/collision_detection/occupancy_map.h | 2 +- .../moveit/collision_detection/test_collision_common_panda.h | 2 +- .../moveit/collision_detection/test_collision_common_pr2.h | 2 +- .../include/moveit/collision_detection/world.h | 2 +- .../include/moveit/collision_detection/world_diff.h | 2 +- .../bullet_integration/basic_types.h | 2 +- .../bullet_integration/bullet_bvh_manager.h | 2 +- .../bullet_integration/bullet_cast_bvh_manager.h | 2 +- .../bullet_integration/bullet_discrete_bvh_manager.h | 2 +- .../bullet_integration/bullet_utils.h | 2 +- .../bullet_integration/contact_checker_common.h | 2 +- .../bullet_integration/ros_bullet_utils.h | 2 +- .../collision_detector_allocator_bullet.h | 2 +- .../collision_detector_bullet_plugin_loader.h | 2 +- .../moveit/collision_detection_bullet/collision_env_bullet.h | 2 +- .../include/moveit/collision_detection_fcl/collision_common.h | 2 +- .../collision_detector_allocator_fcl.h | 2 +- .../collision_detector_fcl_plugin_loader.h | 2 +- .../moveit/collision_detection_fcl/collision_env_fcl.h | 2 +- .../include/moveit/collision_detection_fcl/fcl_compat.h | 2 +- .../collision_common_distance_field.h | 2 +- .../collision_detector_allocator_distance_field.h | 2 +- .../collision_detector_allocator_hybrid.h | 2 +- .../collision_distance_field/collision_distance_field_types.h | 2 +- .../collision_distance_field/collision_env_distance_field.h | 2 +- .../moveit/collision_distance_field/collision_env_hybrid.h | 2 +- .../include/moveit/constraint_samplers/constraint_sampler.h | 2 +- .../moveit/constraint_samplers/constraint_sampler_allocator.h | 2 +- .../moveit/constraint_samplers/constraint_sampler_manager.h | 2 +- .../moveit/constraint_samplers/constraint_sampler_tools.h | 2 +- .../moveit/constraint_samplers/default_constraint_samplers.h | 2 +- .../moveit/constraint_samplers/union_constraint_sampler.h | 2 +- .../include/moveit/controller_manager/controller_manager.h | 2 +- .../include/moveit/distance_field/distance_field.h | 2 +- .../include/moveit/distance_field/find_internal_points.h | 2 +- .../moveit/distance_field/propagation_distance_field.h | 2 +- .../distance_field/include/moveit/distance_field/voxel_grid.h | 2 +- .../include/moveit/dynamics_solver/dynamics_solver.h | 2 +- moveit_core/exceptions/include/moveit/exceptions/exceptions.h | 2 +- .../moveit/kinematic_constraints/kinematic_constraint.h | 2 +- .../include/moveit/kinematic_constraints/utils.h | 2 +- .../include/moveit/kinematics_base/kinematics_base.h | 2 +- .../include/moveit/kinematics_metrics/kinematics_metrics.h | 2 +- moveit_core/macros/include/moveit/macros/class_forward.h | 2 +- moveit_core/macros/include/moveit/macros/console_colors.h | 2 +- moveit_core/macros/include/moveit/macros/declare_ptr.h | 2 +- moveit_core/macros/include/moveit/macros/deprecation.h | 2 +- .../moveit/online_signal_smoothing/acceleration_filter.h | 2 +- .../moveit/online_signal_smoothing/butterworth_filter.h | 2 +- .../include/moveit/online_signal_smoothing/ruckig_filter.h | 2 +- .../moveit/online_signal_smoothing/smoothing_base_class.h | 2 +- .../include/moveit/planning_interface/planning_interface.h | 2 +- .../include/moveit/planning_interface/planning_request.h | 2 +- .../moveit/planning_interface/planning_request_adapter.h | 2 +- .../include/moveit/planning_interface/planning_response.h | 2 +- .../moveit/planning_interface/planning_response_adapter.h | 2 +- .../include/moveit/planning_scene/planning_scene.h | 2 +- moveit_core/robot_model/include/moveit/robot_model/aabb.h | 2 +- .../include/moveit/robot_model/fixed_joint_model.h | 2 +- .../include/moveit/robot_model/floating_joint_model.h | 2 +- .../robot_model/include/moveit/robot_model/joint_model.h | 2 +- .../include/moveit/robot_model/joint_model_group.h | 2 +- .../robot_model/include/moveit/robot_model/link_model.h | 2 +- .../include/moveit/robot_model/planar_joint_model.h | 2 +- .../include/moveit/robot_model/prismatic_joint_model.h | 2 +- .../include/moveit/robot_model/revolute_joint_model.h | 2 +- .../robot_model/include/moveit/robot_model/robot_model.h | 2 +- .../robot_state/include/moveit/robot_state/attached_body.h | 2 +- .../include/moveit/robot_state/cartesian_interpolator.h | 2 +- .../robot_state/include/moveit/robot_state/conversions.h | 2 +- .../robot_state/include/moveit/robot_state/robot_state.h | 2 +- .../include/moveit/robot_trajectory/robot_trajectory.h | 2 +- .../moveit/trajectory_processing/ruckig_traj_smoothing.h | 2 +- .../time_optimal_trajectory_generation.h | 2 +- .../moveit/trajectory_processing/time_parameterization.h | 2 +- .../include/moveit/trajectory_processing/trajectory_tools.h | 2 +- moveit_core/transforms/include/moveit/transforms/transforms.h | 2 +- moveit_core/utils/include/moveit/utils/eigen_test_utils.h | 2 +- moveit_core/utils/include/moveit/utils/lexical_casts.h | 2 +- moveit_core/utils/include/moveit/utils/logger.h | 2 +- moveit_core/utils/include/moveit/utils/message_checks.h | 2 +- moveit_core/utils/include/moveit/utils/moveit_error_code.h | 2 +- moveit_core/utils/include/moveit/utils/rclcpp_utils.h | 2 +- .../utils/include/moveit/utils/robot_model_test_utils.h | 2 +- .../cached_ik_kinematics_plugin-inl.h | 2 +- .../cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h | 2 +- .../cached_ik_kinematics_plugin/detail/GreedyKCenters.h | 2 +- .../cached_ik_kinematics_plugin/detail/NearestNeighbors.h | 2 +- .../cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h | 2 +- .../kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h | 2 +- .../include/moveit/kdl_kinematics_plugin/joint_mimic.h | 2 +- .../moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h | 2 +- .../moveit/srv_kinematics_plugin/srv_kinematics_plugin.h | 2 +- .../chomp_interface/include/chomp_interface/chomp_interface.h | 2 +- .../include/chomp_interface/chomp_planning_context.h | 2 +- .../include/chomp_motion_planner/chomp_cost.h | 2 +- .../include/chomp_motion_planner/chomp_optimizer.h | 2 +- .../include/chomp_motion_planner/chomp_parameters.h | 2 +- .../include/chomp_motion_planner/chomp_planner.h | 2 +- .../include/chomp_motion_planner/chomp_trajectory.h | 2 +- .../include/chomp_motion_planner/chomp_utils.h | 2 +- .../include/chomp_motion_planner/multivariate_gaussian.h | 2 +- .../moveit/ompl_interface/detail/constrained_goal_sampler.h | 2 +- .../moveit/ompl_interface/detail/constrained_sampler.h | 2 +- .../moveit/ompl_interface/detail/constraint_approximations.h | 2 +- .../moveit/ompl_interface/detail/constraints_library.h | 2 +- .../include/moveit/ompl_interface/detail/goal_union.h | 2 +- .../include/moveit/ompl_interface/detail/ompl_constraints.h | 2 +- .../moveit/ompl_interface/detail/projection_evaluators.h | 2 +- .../moveit/ompl_interface/detail/state_validity_checker.h | 2 +- .../moveit/ompl_interface/detail/threadsafe_state_storage.h | 2 +- .../moveit/ompl_interface/model_based_planning_context.h | 2 +- .../include/moveit/ompl_interface/ompl_interface.h | 2 +- .../joint_space/constrained_planning_state_space.h | 2 +- .../joint_space/constrained_planning_state_space_factory.h | 2 +- .../parameterization/joint_space/joint_model_state_space.h | 2 +- .../joint_space/joint_model_state_space_factory.h | 2 +- .../ompl_interface/parameterization/model_based_state_space.h | 2 +- .../parameterization/model_based_state_space_factory.h | 2 +- .../parameterization/work_space/pose_model_state_space.h | 2 +- .../work_space/pose_model_state_space_factory.h | 2 +- .../include/moveit/ompl_interface/planning_context_manager.h | 2 +- .../include/joint_limits_copy/joint_limits.h | 2 +- .../include/joint_limits_copy/joint_limits_rosparam.h | 2 +- .../include/pilz_industrial_motion_planner/capability_names.h | 2 +- .../pilz_industrial_motion_planner/cartesian_trajectory.h | 2 +- .../cartesian_trajectory_point.h | 2 +- .../pilz_industrial_motion_planner/command_list_manager.h | 2 +- .../pilz_industrial_motion_planner/joint_limits_aggregator.h | 2 +- .../pilz_industrial_motion_planner/joint_limits_container.h | 2 +- .../pilz_industrial_motion_planner/joint_limits_extension.h | 2 +- .../joint_limits_interface_extension.h | 2 +- .../pilz_industrial_motion_planner/joint_limits_validator.h | 2 +- .../include/pilz_industrial_motion_planner/limits_container.h | 2 +- .../move_group_sequence_action.h | 2 +- .../move_group_sequence_service.h | 2 +- .../pilz_industrial_motion_planner/path_circle_generator.h | 2 +- .../pilz_industrial_motion_planner.h | 2 +- .../pilz_industrial_motion_planner/plan_components_builder.h | 2 +- .../pilz_industrial_motion_planner/planning_context_base.h | 2 +- .../pilz_industrial_motion_planner/planning_context_circ.h | 2 +- .../pilz_industrial_motion_planner/planning_context_lin.h | 2 +- .../pilz_industrial_motion_planner/planning_context_loader.h | 2 +- .../planning_context_loader_circ.h | 2 +- .../planning_context_loader_lin.h | 2 +- .../planning_context_loader_ptp.h | 2 +- .../pilz_industrial_motion_planner/planning_context_ptp.h | 2 +- .../pilz_industrial_motion_planner/planning_exceptions.h | 2 +- .../include/pilz_industrial_motion_planner/tip_frame_getter.h | 2 +- .../pilz_industrial_motion_planner/trajectory_blend_request.h | 2 +- .../trajectory_blend_response.h | 2 +- .../pilz_industrial_motion_planner/trajectory_blender.h | 2 +- .../trajectory_blender_transition_window.h | 2 +- .../pilz_industrial_motion_planner/trajectory_functions.h | 2 +- .../trajectory_generation_exceptions.h | 2 +- .../pilz_industrial_motion_planner/trajectory_generator.h | 2 +- .../trajectory_generator_circ.h | 2 +- .../pilz_industrial_motion_planner/trajectory_generator_lin.h | 2 +- .../pilz_industrial_motion_planner/trajectory_generator_ptp.h | 2 +- .../pilz_industrial_motion_planner/velocity_profile_atrap.h | 2 +- .../pilz_industrial_motion_planner_testutils/async_test.h | 2 +- .../pilz_industrial_motion_planner_testutils/basecmd.h | 2 +- .../cartesianconfiguration.h | 2 +- .../cartesianpathconstraintsbuilder.h | 2 +- .../include/pilz_industrial_motion_planner_testutils/center.h | 2 +- .../include/pilz_industrial_motion_planner_testutils/checks.h | 2 +- .../include/pilz_industrial_motion_planner_testutils/circ.h | 2 +- .../circ_auxiliary_types.h | 2 +- .../pilz_industrial_motion_planner_testutils/circauxiliary.h | 2 +- .../command_types_typedef.h | 2 +- .../pilz_industrial_motion_planner_testutils/default_values.h | 2 +- .../exception_types.h | 2 +- .../goalconstraintsmsgconvertible.h | 2 +- .../pilz_industrial_motion_planner_testutils/gripper.h | 2 +- .../pilz_industrial_motion_planner_testutils/interim.h | 2 +- .../jointconfiguration.h | 2 +- .../include/pilz_industrial_motion_planner_testutils/lin.h | 2 +- .../pilz_industrial_motion_planner_testutils/motioncmd.h | 2 +- .../motionplanrequestconvertible.h | 2 +- .../include/pilz_industrial_motion_planner_testutils/ptp.h | 2 +- .../robotconfiguration.h | 2 +- .../robotstatemsgconvertible.h | 2 +- .../pilz_industrial_motion_planner_testutils/sequence.h | 2 +- .../testdata_loader.h | 2 +- .../pilz_industrial_motion_planner_testutils/xml_constants.h | 2 +- .../xml_testdata_loader.h | 2 +- .../stomp/include/stomp_moveit/conversion_functions.h | 2 +- moveit_planners/stomp/include/stomp_moveit/cost_functions.h | 2 +- moveit_planners/stomp/include/stomp_moveit/filter_functions.h | 2 +- .../stomp/include/stomp_moveit/math/multivariate_gaussian.h | 2 +- moveit_planners/stomp/include/stomp_moveit/noise_generators.h | 2 +- .../include/stomp_moveit/stomp_moveit_planning_context.h | 2 +- .../stomp/include/stomp_moveit/stomp_moveit_task.h | 2 +- .../stomp/include/stomp_moveit/trajectory_visualization.h | 2 +- .../include/moveit_ros_control_interface/ControllerHandle.h | 2 +- .../action_based_controller_handle.h | 2 +- .../empty_controller_handle.h | 2 +- .../follow_joint_trajectory_controller_handle.h | 2 +- .../gripper_controller_handle.h | 2 +- .../include/moveit_py/moveit_py_utils/copy_ros_msg.h | 2 +- .../include/moveit_py/moveit_py_utils/ros_msg_typecasters.h | 2 +- .../benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h | 2 +- .../benchmarks/include/moveit/benchmarks/BenchmarkOptions.h | 2 +- .../include/moveit/global_planner/global_planner_component.h | 2 +- .../include/moveit/global_planner/global_planner_interface.h | 2 +- .../include/moveit/global_planner/moveit_planning_pipeline.h | 2 +- .../moveit/hybrid_planning_manager/hybrid_planning_events.h | 2 +- .../moveit/hybrid_planning_manager/hybrid_planning_manager.h | 2 +- .../moveit/hybrid_planning_manager/planner_logic_interface.h | 2 +- .../planner_logic_plugins/replan_invalidated_trajectory.h | 2 +- .../moveit/planner_logic_plugins/single_plan_execution.h | 2 +- .../local_constraint_solver_plugins/forward_trajectory.h | 2 +- .../include/moveit/local_planner/feedback_types.h | 2 +- .../moveit/local_planner/local_constraint_solver_interface.h | 2 +- .../include/moveit/local_planner/local_planner_component.h | 2 +- .../moveit/local_planner/trajectory_operator_interface.h | 2 +- .../moveit/trajectory_operator_plugins/simple_sampler.h | 2 +- .../move_group/include/moveit/move_group/capability_names.h | 2 +- .../include/moveit/move_group/move_group_capability.h | 2 +- .../move_group/include/moveit/move_group/move_group_context.h | 2 +- .../moveit_servo/include/moveit_servo/collision_monitor.h | 2 +- moveit_ros/moveit_servo/include/moveit_servo/servo.h | 2 +- moveit_ros/moveit_servo/include/moveit_servo/servo_node.h | 2 +- moveit_ros/moveit_servo/include/moveit_servo/utils/command.h | 2 +- moveit_ros/moveit_servo/include/moveit_servo/utils/common.h | 2 +- .../moveit_servo/include/moveit_servo/utils/datatypes.h | 2 +- .../moveit/occupancy_map_monitor/occupancy_map_monitor.h | 2 +- .../occupancy_map_monitor_middleware_handle.h | 2 +- .../moveit/occupancy_map_monitor/occupancy_map_updater.h | 2 +- .../depth_image_octomap_updater/depth_image_octomap_updater.h | 2 +- .../moveit/lazy_free_space_updater/lazy_free_space_updater.h | 2 +- .../include/moveit/mesh_filter/depth_self_filter_nodelet.h | 2 +- .../mesh_filter/include/moveit/mesh_filter/filter_job.h | 2 +- .../mesh_filter/include/moveit/mesh_filter/gl_mesh.h | 2 +- .../mesh_filter/include/moveit/mesh_filter/gl_renderer.h | 2 +- .../mesh_filter/include/moveit/mesh_filter/mesh_filter.h | 2 +- .../mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h | 2 +- .../mesh_filter/include/moveit/mesh_filter/sensor_model.h | 2 +- .../include/moveit/mesh_filter/stereo_camera_model.h | 2 +- .../include/moveit/mesh_filter/transform_provider.h | 2 +- .../include/moveit/point_containment_filter/shape_mask.h | 2 +- .../pointcloud_octomap_updater/pointcloud_octomap_updater.h | 2 +- .../include/moveit/semantic_world/semantic_world.h | 2 +- .../moveit/collision_plugin_loader/collision_plugin_loader.h | 2 +- .../constraint_sampler_manager_loader.h | 2 +- .../kinematics_plugin_loader/kinematics_plugin_loader.h | 2 +- .../moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h | 2 +- .../moveit_cpp/include/moveit/moveit_cpp/planning_component.h | 2 +- .../include/moveit/plan_execution/plan_execution.h | 2 +- .../include/moveit/plan_execution/plan_representation.h | 2 +- .../include/moveit/planning_pipeline/planning_pipeline.h | 2 +- .../planning_pipeline_interfaces/plan_responses_container.h | 2 +- .../planning_pipeline_interfaces.h | 2 +- .../solution_selection_functions.h | 2 +- .../stopping_criterion_functions.h | 2 +- .../moveit/planning_scene_monitor/current_state_monitor.h | 2 +- .../current_state_monitor_middleware_handle.h | 2 +- .../moveit/planning_scene_monitor/planning_scene_monitor.h | 2 +- .../moveit/planning_scene_monitor/trajectory_monitor.h | 2 +- .../trajectory_monitor_middleware_handle.h | 2 +- .../rdf_loader/include/moveit/rdf_loader/rdf_loader.h | 2 +- .../include/moveit/rdf_loader/synchronized_string_parameter.h | 2 +- .../include/moveit/robot_model_loader/robot_model_loader.h | 2 +- .../trajectory_execution_manager.h | 2 +- .../moveit/common_planning_interface_objects/common_objects.h | 2 +- .../moveit/move_group_interface/move_group_interface.h | 2 +- .../planning_scene_interface/planning_scene_interface.h | 2 +- .../include/moveit/robot_interaction/interaction.h | 2 +- .../include/moveit/robot_interaction/interaction_handler.h | 2 +- .../moveit/robot_interaction/interactive_marker_helpers.h | 2 +- .../include/moveit/robot_interaction/kinematic_options.h | 2 +- .../include/moveit/robot_interaction/kinematic_options_map.h | 2 +- .../include/moveit/robot_interaction/locked_robot_state.h | 2 +- .../include/moveit/robot_interaction/robot_interaction.h | 2 +- moveit_ros/tests/include/parameter_name_list.h | 3 ++- .../include/moveit/trajectory_cache/trajectory_cache.h | 2 +- .../motion_planning_rviz_plugin/interactive_marker_display.h | 2 +- .../motion_planning_rviz_plugin/motion_planning_display.h | 2 +- .../motion_planning_rviz_plugin/motion_planning_frame.h | 2 +- .../motion_planning_frame_joints_widget.h | 2 +- .../motion_planning_param_widget.h | 2 +- .../moveit/planning_scene_rviz_plugin/background_processing.h | 2 +- .../planning_scene_rviz_plugin/planning_scene_display.h | 2 +- .../moveit/robot_state_rviz_plugin/robot_state_display.h | 2 +- .../include/moveit/rviz_plugin_render_tools/octomap_render.h | 2 +- .../moveit/rviz_plugin_render_tools/planning_link_updater.h | 2 +- .../moveit/rviz_plugin_render_tools/planning_scene_render.h | 2 +- .../include/moveit/rviz_plugin_render_tools/render_shapes.h | 2 +- .../rviz_plugin_render_tools/robot_state_visualization.h | 2 +- .../moveit/rviz_plugin_render_tools/trajectory_panel.h | 2 +- .../rviz_plugin_render_tools/trajectory_visualization.h | 2 +- .../include/ogre_helpers/mesh_shape.h | 2 +- .../moveit/trajectory_rviz_plugin/trajectory_display.h | 2 +- .../warehouse/include/moveit/warehouse/constraints_storage.h | 2 +- .../include/moveit/warehouse/moveit_message_storage.h | 2 +- .../include/moveit/warehouse/planning_scene_storage.h | 2 +- .../include/moveit/warehouse/planning_scene_world_storage.h | 2 +- moveit_ros/warehouse/include/moveit/warehouse/state_storage.h | 2 +- .../include/moveit/warehouse/trajectory_constraints_storage.h | 2 +- .../warehouse/include/moveit/warehouse/warehouse_connector.h | 2 +- .../include/moveit_setup_app_plugins/launch_bundle.h | 2 +- .../include/moveit_setup_app_plugins/launches.h | 2 +- .../include/moveit_setup_app_plugins/launches_config.h | 2 +- .../include/moveit_setup_app_plugins/launches_widget.h | 2 +- .../include/moveit_setup_app_plugins/perception.h | 2 +- .../include/moveit_setup_app_plugins/perception_config.h | 2 +- .../include/moveit_setup_app_plugins/perception_widget.h | 2 +- .../include/moveit_setup_assistant/navigation_widget.h | 2 +- .../include/moveit_setup_assistant/setup_assistant_widget.h | 2 +- .../include/moveit_setup_controllers/control_xacro_config.h | 2 +- .../include/moveit_setup_controllers/controller_edit_widget.h | 2 +- .../include/moveit_setup_controllers/controllers.h | 2 +- .../include/moveit_setup_controllers/controllers_config.h | 2 +- .../include/moveit_setup_controllers/controllers_widget.h | 2 +- .../include/moveit_setup_controllers/included_xacro_config.h | 2 +- .../include/moveit_setup_controllers/modified_urdf_config.h | 2 +- .../include/moveit_setup_controllers/moveit_controllers.h | 2 +- .../moveit_setup_controllers/moveit_controllers_config.h | 2 +- .../include/moveit_setup_controllers/ros2_controllers.h | 2 +- .../moveit_setup_controllers/ros2_controllers_config.h | 2 +- .../include/moveit_setup_controllers/urdf_modifications.h | 2 +- .../moveit_setup_controllers/urdf_modifications_widget.h | 2 +- .../include/moveit_setup_core_plugins/author_information.h | 2 +- .../moveit_setup_core_plugins/author_information_widget.h | 2 +- .../include/moveit_setup_core_plugins/configuration_files.h | 2 +- .../moveit_setup_core_plugins/configuration_files_widget.h | 2 +- .../include/moveit_setup_core_plugins/start_screen.h | 2 +- .../include/moveit_setup_core_plugins/start_screen_widget.h | 2 +- .../include/moveit_setup_framework/config.h | 2 +- .../moveit_setup_framework/data/package_settings_config.h | 2 +- .../include/moveit_setup_framework/data/srdf_config.h | 2 +- .../include/moveit_setup_framework/data/urdf_config.h | 2 +- .../include/moveit_setup_framework/data_warehouse.h | 2 +- .../include/moveit_setup_framework/generated_file.h | 2 +- .../include/moveit_setup_framework/generated_time.h | 2 +- .../include/moveit_setup_framework/qt/double_list_widget.h | 2 +- .../include/moveit_setup_framework/qt/helper_widgets.h | 2 +- .../include/moveit_setup_framework/qt/rviz_panel.h | 2 +- .../include/moveit_setup_framework/qt/setup_step_widget.h | 2 +- .../moveit_setup_framework/qt/xml_syntax_highlighter.h | 2 +- .../include/moveit_setup_framework/setup_step.h | 2 +- .../include/moveit_setup_framework/templates.h | 2 +- .../include/moveit_setup_framework/testing_utils.h | 2 +- .../include/moveit_setup_framework/utilities.h | 2 +- .../include/moveit_setup_simulation/simulation.h | 2 +- .../include/moveit_setup_simulation/simulation_widget.h | 2 +- .../moveit_setup_srdf_plugins/collision_linear_model.h | 2 +- .../moveit_setup_srdf_plugins/collision_matrix_model.h | 2 +- .../moveit_setup_srdf_plugins/compute_default_collisions.h | 2 +- .../include/moveit_setup_srdf_plugins/default_collisions.h | 2 +- .../moveit_setup_srdf_plugins/default_collisions_widget.h | 2 +- .../include/moveit_setup_srdf_plugins/end_effectors.h | 2 +- .../include/moveit_setup_srdf_plugins/end_effectors_widget.h | 2 +- .../include/moveit_setup_srdf_plugins/group_edit_widget.h | 2 +- .../include/moveit_setup_srdf_plugins/group_meta_config.h | 2 +- .../moveit_setup_srdf_plugins/kinematic_chain_widget.h | 2 +- .../include/moveit_setup_srdf_plugins/passive_joints.h | 2 +- .../include/moveit_setup_srdf_plugins/passive_joints_widget.h | 2 +- .../include/moveit_setup_srdf_plugins/planning_groups.h | 2 +- .../moveit_setup_srdf_plugins/planning_groups_widget.h | 2 +- .../include/moveit_setup_srdf_plugins/robot_poses.h | 2 +- .../include/moveit_setup_srdf_plugins/robot_poses_widget.h | 2 +- .../include/moveit_setup_srdf_plugins/rotated_header_view.h | 2 +- .../include/moveit_setup_srdf_plugins/srdf_step.h | 2 +- .../include/moveit_setup_srdf_plugins/virtual_joints.h | 2 +- .../include/moveit_setup_srdf_plugins/virtual_joints_widget.h | 2 +- 377 files changed, 379 insertions(+), 378 deletions(-) diff --git a/moveit/scripts/create_deprecated_headers.py b/moveit/scripts/create_deprecated_headers.py index 9a30db1a41..5f992c94bf 100755 --- a/moveit/scripts/create_deprecated_headers.py +++ b/moveit/scripts/create_deprecated_headers.py @@ -85,7 +85,7 @@ class DeprecatedHeader: def __init__(self, hpp: HppFile): self.hpp = hpp self.path = hpp.path.with_suffix(".h") - self.prefix = f"This file was autogenerated by {__file__}" + self.prefix = f"/* This file was autogenerated by {Path(__file__).name}" self.warn = '#pragma message(".h header is obsolete. Please use the .hpp")' self.contents = self.contents() @@ -123,7 +123,7 @@ def parse_args(args: List) -> bool: answer = input("Proceed to generate? (y/n): ") apply = answer.lower() == "y" if apply: - print("Proceeding to generate {} .h files...") + print(f"Proceeding to generate {len(processed)} .h files...") to_generate = [DeprecatedHeader(hpp) for hpp in processed] _ = [open(h.path, "w").write(h.contents) for h in to_generate] print("Done.") diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h index f947e9f0cc..32788fa020 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h index 178bf77d66..14ad0c66a2 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h index 8880966f60..cd15aff7f5 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h index 224c49bb9c..5cbb180837 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h index 77f9d45120..9f595cb590 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h index 39cae0f308..dc2be05a21 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h index 5a1f30343b..cc06a592ca 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h index 57e8da8a8d..e3a7410be7 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h index 241f4c017d..f4cc4c71cb 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h index 9f5fedb060..258eadba21 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h b/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h index 8ff270cca7..8b690149f8 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h index c34a810726..2174eae909 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h index 5609dd09e2..653fa8358a 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/world.h b/moveit_core/collision_detection/include/moveit/collision_detection/world.h index bb82985627..363fabac62 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/world.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/world.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h b/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h index 2935f0ee89..fa9275490e 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h index 6cebcf63a8..9f27078b55 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (Apache License) diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h index 7fb8b16ae4..fbf89b664b 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD-2-Clause) diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h index 3afb39f0a5..a35972e0df 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD-2-Clause) diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h index 24897d1d68..f26718366e 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD-2-Clause) diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h index 72d3579bf7..de55dc4cc3 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD-2-Clause) diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h index 150c7b92dd..0f512eece7 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (Apache License) diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h index d1d6f17cc6..70c2ff3211 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (Apache License) diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h index 1a381cfef0..1c5ebb83c6 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h index df1db499fa..3f751e56b9 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h index afe53ee15f..109ca5e612 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h index 6511f712ce..f745818943 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h index a99ad8a198..10fe6917b7 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h index 9a107a3074..88020bd96f 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h index ff6cd9eb15..d6bf6c7a96 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h index 5ac09571d1..334b6e6f22 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h index 5dab2cb444..a402e27511 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h index 4929f799c1..2edaf14365 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h index 1b53935513..06476f376b 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h index f2a160878f..b2bc6657a7 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h index 7c9457b887..ff51c5c821 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h index 67abbd33c2..4fb0a539f9 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h index d570465094..87b5930d74 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h index ba8cf6014d..a335db3f44 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h index cab5b3a53a..b3085622eb 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h index e440f534d3..3a8ea727a0 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h index 82f4603be6..f14d98795e 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h index bb3d9d33b7..4d36a6b68d 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h b/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h index 760570e526..900fd208bc 100644 --- a/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h +++ b/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/distance_field/include/moveit/distance_field/distance_field.h b/moveit_core/distance_field/include/moveit/distance_field/distance_field.h index 5409c64695..4ffefecc07 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/distance_field.h +++ b/moveit_core/distance_field/include/moveit/distance_field/distance_field.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h b/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h index 1ede20f322..fa80414aaa 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h +++ b/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h b/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h index aaa0e6cd14..a42ad2f184 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h +++ b/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h b/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h index 82c5bc37ac..94c8c2e415 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h +++ b/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h b/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h index 84bd3f6a59..21f7d24b23 100644 --- a/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h +++ b/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/exceptions/include/moveit/exceptions/exceptions.h b/moveit_core/exceptions/include/moveit/exceptions/exceptions.h index f2b561eb36..46d7f83af2 100644 --- a/moveit_core/exceptions/include/moveit/exceptions/exceptions.h +++ b/moveit_core/exceptions/include/moveit/exceptions/exceptions.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h index dda518de8a..b43d41bad0 100644 --- a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h +++ b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h index 638d456339..7a23af9225 100644 --- a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h +++ b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h index ba8eba1cdf..b9d6469aa6 100644 --- a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h +++ b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h b/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h index 69fd46a315..b107377001 100644 --- a/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h +++ b/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/macros/include/moveit/macros/class_forward.h b/moveit_core/macros/include/moveit/macros/class_forward.h index 5a5deeedb3..31191ea2ab 100644 --- a/moveit_core/macros/include/moveit/macros/class_forward.h +++ b/moveit_core/macros/include/moveit/macros/class_forward.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/macros/include/moveit/macros/console_colors.h b/moveit_core/macros/include/moveit/macros/console_colors.h index 598ebe97e3..88d2602fa2 100644 --- a/moveit_core/macros/include/moveit/macros/console_colors.h +++ b/moveit_core/macros/include/moveit/macros/console_colors.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/macros/include/moveit/macros/declare_ptr.h b/moveit_core/macros/include/moveit/macros/declare_ptr.h index 559df2c011..29a2e84500 100644 --- a/moveit_core/macros/include/moveit/macros/declare_ptr.h +++ b/moveit_core/macros/include/moveit/macros/declare_ptr.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/macros/include/moveit/macros/deprecation.h b/moveit_core/macros/include/moveit/macros/deprecation.h index 122ddb8114..973eef48ac 100644 --- a/moveit_core/macros/include/moveit/macros/deprecation.h +++ b/moveit_core/macros/include/moveit/macros/deprecation.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h index 7c017835e0..b0df2730d5 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h index b5c1daa322..d69bbdc330 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h index fb3821e735..1712a8f2a8 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h index f7c69a7cca..df2317c75a 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h index 7793132fcb..a1a2117cf6 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h index 01437b9dca..796433821f 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h index d0762020a2..94225d92e5 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h index f28daaa97a..6b07a7acec 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h index 565761023a..b26ff6cf0b 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h index 8f44903795..796a096106 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/robot_model/include/moveit/robot_model/aabb.h b/moveit_core/robot_model/include/moveit/robot_model/aabb.h index 86bc4f6efc..e468978776 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/aabb.h +++ b/moveit_core/robot_model/include/moveit/robot_model/aabb.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h index 6f039b94ba..44a056b947 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h index 26291fd095..4c7f5c5edd 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/robot_model/include/moveit/robot_model/joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/joint_model.h index 35aa6a15c3..8acfaf27e8 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/joint_model.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h index 69643b5292..1810fc35c0 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h +++ b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/robot_model/include/moveit/robot_model/link_model.h b/moveit_core/robot_model/include/moveit/robot_model/link_model.h index dd0d74a5a6..0e795d0663 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/link_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/link_model.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h index 7cb2dde674..3e5ab7f4d4 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h index a49ae38ca4..0c481c3b26 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h index 6fb880325e..059c7b25ae 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h index 92161465e7..f5b94e1e8e 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/robot_state/include/moveit/robot_state/attached_body.h b/moveit_core/robot_state/include/moveit/robot_state/attached_body.h index a6ea3ae946..5cf4a30a1f 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/attached_body.h +++ b/moveit_core/robot_state/include/moveit/robot_state/attached_body.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h b/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h index 309d850268..996f6d29b9 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h +++ b/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/robot_state/include/moveit/robot_state/conversions.h b/moveit_core/robot_state/include/moveit/robot_state/conversions.h index 958016f790..5d3bd8812e 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/conversions.h +++ b/moveit_core/robot_state/include/moveit/robot_state/conversions.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h index 7c3741893d..06d33c1e71 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h +++ b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h index 961c0db49f..c19a1893c0 100644 --- a/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h +++ b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h index 20220875dc..5d1b609b2a 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /******************************************************************************* * BSD 3-Clause License diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h index 1e86073e6a..b5a2566778 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /* * Copyright (c) 2011-2012, Georgia Tech Research Corporation diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h index 7e644e70dd..b10e52cef2 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py #pragma once diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h index 3c7c5a6c26..4e922ad63a 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/transforms/include/moveit/transforms/transforms.h b/moveit_core/transforms/include/moveit/transforms/transforms.h index 5c88a25cbd..53ac9b0ab5 100644 --- a/moveit_core/transforms/include/moveit/transforms/transforms.h +++ b/moveit_core/transforms/include/moveit/transforms/transforms.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/utils/include/moveit/utils/eigen_test_utils.h b/moveit_core/utils/include/moveit/utils/eigen_test_utils.h index e2b203ea07..cd680b07ce 100644 --- a/moveit_core/utils/include/moveit/utils/eigen_test_utils.h +++ b/moveit_core/utils/include/moveit/utils/eigen_test_utils.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/utils/include/moveit/utils/lexical_casts.h b/moveit_core/utils/include/moveit/utils/lexical_casts.h index 7c60075c2b..0c9b528cb2 100644 --- a/moveit_core/utils/include/moveit/utils/lexical_casts.h +++ b/moveit_core/utils/include/moveit/utils/lexical_casts.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/utils/include/moveit/utils/logger.h b/moveit_core/utils/include/moveit/utils/logger.h index 36ec67f29b..3109573f57 100644 --- a/moveit_core/utils/include/moveit/utils/logger.h +++ b/moveit_core/utils/include/moveit/utils/logger.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/utils/include/moveit/utils/message_checks.h b/moveit_core/utils/include/moveit/utils/message_checks.h index a42fe726ed..137fcdb61e 100644 --- a/moveit_core/utils/include/moveit/utils/message_checks.h +++ b/moveit_core/utils/include/moveit/utils/message_checks.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/utils/include/moveit/utils/moveit_error_code.h b/moveit_core/utils/include/moveit/utils/moveit_error_code.h index fd06af4808..fd822911d1 100644 --- a/moveit_core/utils/include/moveit/utils/moveit_error_code.h +++ b/moveit_core/utils/include/moveit/utils/moveit_error_code.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_core/utils/include/moveit/utils/rclcpp_utils.h b/moveit_core/utils/include/moveit/utils/rclcpp_utils.h index c80ec49c27..4c278c3f7e 100644 --- a/moveit_core/utils/include/moveit/utils/rclcpp_utils.h +++ b/moveit_core/utils/include/moveit/utils/rclcpp_utils.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /* * Copyright (C) 2009, Willow Garage, Inc. diff --git a/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h b/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h index 0e7c572005..700deef054 100644 --- a/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h +++ b/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h index 2f7509f35e..59660a0413 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h index a7345a379e..b94b1c7141 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h index 884f9972d8..a09f8dd9e8 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h index 2582f3db00..3bfe208998 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h index fd81e40bc1..54986b1bfd 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h index 7218a0cb11..4e49b63e3d 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h +++ b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py // Copyright (C) 2007 Ruben Smits diff --git a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h index b88ae07e69..7dc1dc9359 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h +++ b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h index 637c72739e..17e49299bc 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h +++ b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h b/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h index eb26255f5b..379c9ea58f 100644 --- a/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h +++ b/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h index 5cac19f060..1e8810c7e4 100644 --- a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h +++ b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h index f6da1a348b..bc6b3260d1 100644 --- a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h +++ b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h index 61f86afd60..b4cfb262f4 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h index a7d76da52f..876f704e0d 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h index 72c8edd111..18159fb926 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h index d037f1449e..b8470be276 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h index 9c62527caa..a474237f28 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h index 22c983ad1a..b5083d5704 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h index 77a7791205..91c82c71f6 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h index d3a6d9a9e6..c5d4133de9 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h index 80b3463f68..74b74a47b5 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h index 59fe5b5b8f..8aea86a2c1 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h index 1af59ae7cb..7b1e5352ec 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h index 8506ba061f..47b5e692ae 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h index 77120f01eb..4a794a0a46 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h index d7162e02d2..d571345b32 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h index 6177cdb68e..5ba2399fde 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h index 71f27870be..d23d0a67be 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h index 3bba66f6ac..3be8a37b08 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h index 2c50a0c40a..c576d9ddf8 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h index 8672745ceb..75f8bffe40 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h index e175e1bbe9..dade98b081 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h index f11ee67fcb..b18552862d 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h index 05eed88720..ecc28bfbb1 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h index 3e79a83868..8ac2f9c7b6 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h index e157e9826f..e2e60afe93 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h index 23f4466084..382f25f978 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h index ba3cdee5c8..19f9959391 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h index 1840319ad9..8c33369f29 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h index ed02e48a4c..c5309163d8 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py // Copyright 2020 PAL Robotics S.L. // diff --git a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h index 8393b5c3bd..fa448448d7 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py // Copyright 2020 PAL Robotics S.L. // diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h index 07151242dc..e1b4ada1b0 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h index f162963b78..e5406d26ab 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h index 5f7ff9684b..f32893c680 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h index 4ed08a2a50..06a9998411 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h index ee948c6e78..5e02810d0f 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h index a6ef5747b2..b194892de2 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h index 8c5679f0bd..e71ceedf11 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h index 66b56fc80d..24e0a746dd 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h index 3ee7e04a43..d517e9848b 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h index 235a547d46..d3c90a4dd0 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h index 5905e95ef4..8a00a0b90a 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h index bf28634c9a..01dfba2c00 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h index f3ef612240..b574860af5 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h index 0a1c4f8d09..76008b213d 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h index ab9616d9c3..559042c9ab 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h index 6583b46415..b0d4f87c9f 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h index d8bfc05a0c..11a2631153 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h index 5a741fd625..ec5e3f093c 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h index c409541eda..69e4a4999f 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h index 82b5905e12..03e4fc1785 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h index f753fff0c5..ea860edca1 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h index 67803c12ac..f6cbed2a3c 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h index e1297ecb5b..4df443aad7 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h index b57e8de934..ba5a6392d9 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h index b42792d0b1..cb048deee8 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h index 9c475d03eb..142da2e4f3 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h index 3a752f3890..b6568bd44f 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h index 54f924676e..11dd9c87f5 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h index 60c2e69084..b92c92825c 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h index f68c11ba9d..876fb40906 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h index 8b52a07665..f5c2d14d73 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h index 98e7e6c474..8e81e36531 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h index c5c80e7d57..6eb333780e 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h index b6b2f1b5de..eb4b923f0a 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h index 0f7a7c1995..04e276ad4d 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h index 458374f007..eb63347321 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h index 71b2442dcc..6800c97b01 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /* * Copyright (c) 2018 Pilz GmbH & Co. KG diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h index 4b9e6396cb..53403a5cf9 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h index d437e18359..a99a219943 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h index aa1939b311..b8aa4aeb8e 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h index c8696396ae..a0a15f852a 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h index 1c30c39baa..b7ca93b9fe 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h index 3526cc4d36..d6bcc82af2 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h index 8dda9ec397..e4036f47f5 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h index 6434f3a6d7..dc414d15b1 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h index 337eaa879e..c19c1b34c8 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h index b98e9fac33..1a7b6f3b14 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h index 6f7729d705..2e2546c62d 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h index e8b17f0722..6b2f5ff682 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h index df970b16e0..780afcc42b 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h index 45c6380b9f..bf88bcc041 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h index aafabf7f81..513808cda5 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h index d6bca42443..355c27c03a 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h index 1c7d5d8a04..a95e7ad5d8 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h index a29180a2d1..d3ede32789 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h index 01d2d2883d..4ca3e49d09 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h index a72867b9a8..b7e064e6b0 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h index bcfbe8b18c..1a74c4b9e0 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h index bcd39c48ec..f7a5aac8cb 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h index e116a5c43a..090fbddda7 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h index b7df94a4f8..63849c4fa2 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h index 0b8ebfd9f5..b3d05d6816 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h b/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h index 0098ef57cb..3aa2acba49 100644 --- a/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h +++ b/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/stomp/include/stomp_moveit/cost_functions.h b/moveit_planners/stomp/include/stomp_moveit/cost_functions.h index 3c1988f56d..82855dcb0d 100644 --- a/moveit_planners/stomp/include/stomp_moveit/cost_functions.h +++ b/moveit_planners/stomp/include/stomp_moveit/cost_functions.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/stomp/include/stomp_moveit/filter_functions.h b/moveit_planners/stomp/include/stomp_moveit/filter_functions.h index 384383e8b9..a9087d42ad 100644 --- a/moveit_planners/stomp/include/stomp_moveit/filter_functions.h +++ b/moveit_planners/stomp/include/stomp_moveit/filter_functions.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h b/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h index c241d73e1d..65d7826583 100644 --- a/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h +++ b/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/stomp/include/stomp_moveit/noise_generators.h b/moveit_planners/stomp/include/stomp_moveit/noise_generators.h index c0104549fc..04b88428f9 100644 --- a/moveit_planners/stomp/include/stomp_moveit/noise_generators.h +++ b/moveit_planners/stomp/include/stomp_moveit/noise_generators.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h index cd2ee4254b..e85568bde4 100644 --- a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h +++ b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h index 9809902ec9..adc55d8746 100644 --- a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h +++ b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h b/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h index 4c0b5874b8..bf48fa27c3 100644 --- a/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h +++ b/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h b/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h index 44101e7fe7..7e61a64424 100644 --- a/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h +++ b/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h index 78f11dd7ca..8283634ece 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h index 5ba70c2d14..e52a9cd1f3 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h index 8747396438..aba78df9fd 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h index 867c0b98d3..bf54bfe6eb 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h index 0e7f2561dd..04b6f9e73b 100644 --- a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h +++ b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h index 0fdaef0172..e40b0f9d49 100644 --- a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h +++ b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h index 0e361b8079..87724c3bc9 100644 --- a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h +++ b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h index 9b540f0445..4496cb2cb5 100644 --- a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h +++ b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h index 4c9fce2be8..6099242c3b 100644 --- a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h +++ b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h index 34fe430220..04ab97f3b3 100644 --- a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h +++ b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h b/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h index 2337137570..ed299a6382 100644 --- a/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h +++ b/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h index 98e4235220..e0cc08fa9b 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h index 8732bfd685..cc12500b15 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h index 33be18b690..1bac9b1d93 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h index 14c62e273d..8db3475151 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h index 24f07f848b..72e257917a 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h b/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h index 568e68a914..0990d826e5 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h +++ b/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h index a7bce77b87..cb4c236ded 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h index 8682c129bb..f989d710f6 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h index 01a6acb893..24da0a6a9f 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h index f325f59993..6e7ff5be29 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h b/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h index cbbfff6080..2e22ae6920 100644 --- a/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h +++ b/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/move_group/include/moveit/move_group/capability_names.h b/moveit_ros/move_group/include/moveit/move_group/capability_names.h index 3674dfd67d..57de83608a 100644 --- a/moveit_ros/move_group/include/moveit/move_group/capability_names.h +++ b/moveit_ros/move_group/include/moveit/move_group/capability_names.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h b/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h index 1e8a719d90..59128f038c 100644 --- a/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h +++ b/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/move_group/include/moveit/move_group/move_group_context.h b/moveit_ros/move_group/include/moveit/move_group/move_group_context.h index 8719332728..80ba82e060 100644 --- a/moveit_ros/move_group/include/moveit/move_group/move_group_context.h +++ b/moveit_ros/move_group/include/moveit/move_group/move_group_context.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h b/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h index 4a8d2a9d5a..83cf6350c9 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /******************************************************************************* * BSD 3-Clause License diff --git a/moveit_ros/moveit_servo/include/moveit_servo/servo.h b/moveit_ros/moveit_servo/include/moveit_servo/servo.h index ad86c54637..dd4afc5f1a 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/servo.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/servo.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /******************************************************************************* * BSD 3-Clause License diff --git a/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h b/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h index 474a259453..a645dae89c 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /******************************************************************************* * BSD 3-Clause License diff --git a/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h b/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h index af75e56f7c..4c5850788a 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /******************************************************************************* * BSD 3-Clause License diff --git a/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h b/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h index d83cd75517..d94dfebc91 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /******************************************************************************* * BSD 3-Clause License diff --git a/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h b/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h index aa21b302ed..18aa3ae3fb 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /******************************************************************************* * BSD 3-Clause License diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h index cc74d16746..998c95c996 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h index 1df426fcb4..c832e0a2b3 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h index f41a834775..da169c926e 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h b/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h index 43dfa59d58..e1eb7ee74b 100644 --- a/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h +++ b/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h b/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h index 87828d1674..2014030a33 100644 --- a/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h +++ b/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h index 6934c7f0ae..946e610958 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h index 01b50ef7b1..6705905119 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h index 02de95c7e9..d3f03044f8 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h index 8832e874f5..d8e964cbc1 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h index aa64e21c4e..8491e1031e 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h index af27294caf..dac4ce8143 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h index ec8ac0b1df..36eb2bbfbe 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h index 58a5f4ef53..84f362a4f6 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h index b00a502882..7975ea5384 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h b/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h index b8a32e7d50..3d5f11bfa1 100644 --- a/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h +++ b/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h b/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h index 2d51dea8a7..e078edde8c 100644 --- a/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h +++ b/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h index 6a59bacb08..97dea4c66a 100644 --- a/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h +++ b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h b/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h index 48b28df3dd..10867ef3d5 100644 --- a/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h +++ b/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h b/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h index d1c37111cb..6c7259dce7 100644 --- a/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h +++ b/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h b/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h index fe9d9d8ef4..a9803a7726 100644 --- a/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h +++ b/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h index 74a6efd12c..52be4c198b 100644 --- a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h +++ b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h index 82c99aa655..6c089c3a4b 100644 --- a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h +++ b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h index a9f111687c..e3f62fb566 100644 --- a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h +++ b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h index 209cae31b5..05b1af9659 100644 --- a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h +++ b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h index afc72fb212..7106db6d10 100644 --- a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h +++ b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h index 7c18b123e1..5ab0fa0643 100644 --- a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h index 04bef95ac5..e797a51496 100644 --- a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h index 66baa7236f..1ab3c90ff9 100644 --- a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h index 1524500528..d5607b3f39 100644 --- a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h index 4cfe88100b..2e7bb4f87b 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h index d18a6e4ad6..515f7c4aaf 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h index c968bc632e..b9ea60230c 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h index 39c2e6aa63..4494a22fd3 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h index 0792db4e34..20fc112e29 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h index 4bef512b1d..f1172ccb2d 100644 --- a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h +++ b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h index 811c39f9ac..24969ed02e 100644 --- a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h +++ b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h b/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h index ba8b028043..6e826ee618 100644 --- a/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h +++ b/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h index 4155e62d50..0a1863d34e 100644 --- a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h +++ b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h b/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h index f3612f2133..2367e00a5b 100644 --- a/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h +++ b/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h index c55597400f..99547ced31 100644 --- a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h +++ b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h b/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h index 330269b521..fc014269d9 100644 --- a/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h +++ b/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h index ea4815f092..11f7631883 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h index 392886b4cf..dd16a14ff0 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h index 4e5528fb47..e186be35e7 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h index ed4cf0f624..bc3979c334 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h index c9d0ee92de..e802e3c63f 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h index c5812b38e6..b786fd5ad4 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h index c0992df00d..2a6ff0236a 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/tests/include/parameter_name_list.h b/moveit_ros/tests/include/parameter_name_list.h index aa065e0e12..2bc307da12 100644 --- a/moveit_ros/tests/include/parameter_name_list.h +++ b/moveit_ros/tests/include/parameter_name_list.h @@ -1,4 +1,5 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py + /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h b/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h index 3c193ab515..da046322d6 100644 --- a/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h +++ b/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py // Copyright 2024 Intrinsic Innovation LLC. // diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h index 127b36803d..9c5a0d8d51 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /* * Copyright (c) 2008, Willow Garage, Inc. diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h index 59df71ad3c..cd23d28c26 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h index 1d5ba0c1d2..c7ee73240f 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h index 3c4adab291..b8eb29431e 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h index 761e2b3d3f..62500a8220 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h index 63dd61ffa3..6251771f46 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h index a1e5b39f99..4489c97db7 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h b/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h index 897a8a6eca..0223608580 100644 --- a/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h +++ b/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h index d966a246de..f0ec0a9e04 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h index 1316751d95..0fa1d1a7e4 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h index 8624e942de..19b0d68dc7 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h index 0ce814312c..7eecb64aae 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h index 0adc7ab31d..114e1361cb 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h index feb1400e4b..49e90558eb 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h index a542878632..32a4f4f734 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h index 40aab1a5d6..c3acb69a62 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /* * Copyright (c) 2008, Willow Garage, Inc. diff --git a/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h b/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h index 34d1101690..5b07a99568 100644 --- a/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h +++ b/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h index 577ab40a49..438e342a3d 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h index f12b9edecf..c7e27ebf39 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h index f7a5584261..b34bdba411 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h index b06ebb699b..b56789341b 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h index d3946532f5..1a547f3f3c 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h index 41061f7cbf..e88c776cb4 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h b/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h index 825175e9de..2fd3c2c72b 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h index 2e43b89db2..7e4aa488b7 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h index 366beb853c..e9fbf96a8c 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h index 38342c56dd..d6d0a32ac8 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h index eb3f96db93..dbce78db54 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h index ef345878e2..ecc43898c6 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h index 98eee2283d..674fe4135c 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h index ac83baedbd..5a860a983b 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h index 45f878256d..5c2d2cb551 100644 --- a/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h +++ b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h index 24ff1576b7..a0e51ad1ed 100644 --- a/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h +++ b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h index 0bb89549e9..ed33c57b8a 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h index f62776370c..f71f7f921f 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h index c554d9b5ed..9ada360418 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h index 6398bbb91a..abc433642e 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h index 8ca21f75d6..1747028628 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h index 84177205da..0f279178bf 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h index 1df30c1d49..673fd16e33 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h index fb1d3d413b..fa333b191b 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h index 1196bb1223..84a9adfc56 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h index 5c6a5a7364..6219447841 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h index e473047b50..be7893a5fd 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h index d5eb9ff70a..92d6d79ca3 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h index 62169b1846..131bdfc222 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h index 46ad9305ec..8bd25faa22 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h index 75df4663e6..7a776e0302 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h index 69adfd0b1c..2530c6dacf 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h index f2bdde815e..7ef7ca3794 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h index 4615293d29..8b0fe02c27 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h index c53da02446..8ea6c9b753 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h index 390a96073b..d89217b948 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h index 3c11ad1929..236f5befe4 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h index c24a63ed8e..f0bc016767 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h index 393e276630..c811e7e0ee 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h index d50fe55346..2bb1db533e 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h index c9a5db012a..c170ec6efd 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h index 6ec71b3a2a..05431a674b 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h index 4fa521fb68..79927f2725 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h index ae90d03442..c5370b4725 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h index 582cc68831..523872683e 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h index e71ef399c6..6892c15540 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h index 4a8a0b1388..5ded47360a 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h index 5e921d3e33..5d9694c2ca 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h index 950e91556b..f5d15dd479 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h index 4c5c1eb807..c79574db2f 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h index 81d44828b2..fc03d0a9bc 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h index 3b882053d0..e99c122d1c 100644 --- a/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h +++ b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h index b353e3b699..155740b1fb 100644 --- a/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h +++ b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h index db7b396e57..9820974bc9 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h index 875df207e4..f47ed4adac 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h index e0ff4457c0..19effe012e 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h index 823b6cc5c8..a378ebb7a2 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h index 8da3914fb1..5aac2d9346 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h index 0dc085d556..1b8f537562 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h index d0d3998039..0c6b0b3881 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h index b8ce516ad6..16875b3104 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h index fdf4de54e2..7367dd60f1 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h index 6f44c9eda1..246da3d7c3 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h index b91f86e5cc..67a2f10b36 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h index 0b4669b21a..02cc1ad029 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h index 51f179cbcf..d53ecfa980 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h index cd6d2d4cf7..c993cd81cb 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h index 6a2621c9c4..a53241e51b 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h index a4edfe5f2a..cbbd6d8ce3 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h index 1a980fdc5d..abc715d8ba 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h index dd7daea414..9d9d2554bb 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h index 3a2097394c..95d18097d0 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h index d5f8fdfd65..cd7f9332cb 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h @@ -1,4 +1,4 @@ -This file was autogenerated by / root / ws_moveit / src / moveit2 /./ moveit / scripts / create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py /********************************************************************* * Software License Agreement (BSD License) From 3b0ad7401b9bcac88fe1abea664f8b9268b6bdb7 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Thu, 21 Nov 2024 21:47:14 +0000 Subject: [PATCH 42/53] Temporarily disables deprecation msg to reduce compiler spam --- .../allvalid/collision_detector_allocator_allvalid.h | 2 +- .../collision_detection/allvalid/collision_env_allvalid.h | 2 +- .../include/moveit/collision_detection/collision_common.h | 2 +- .../moveit/collision_detection/collision_detector_allocator.h | 2 +- .../include/moveit/collision_detection/collision_env.h | 2 +- .../include/moveit/collision_detection/collision_matrix.h | 2 +- .../moveit/collision_detection/collision_octomap_filter.h | 2 +- .../include/moveit/collision_detection/collision_plugin.h | 2 +- .../include/moveit/collision_detection/collision_plugin_cache.h | 2 +- .../include/moveit/collision_detection/collision_tools.h | 2 +- .../include/moveit/collision_detection/occupancy_map.h | 2 +- .../moveit/collision_detection/test_collision_common_panda.h | 2 +- .../moveit/collision_detection/test_collision_common_pr2.h | 2 +- .../include/moveit/collision_detection/world.h | 2 +- .../include/moveit/collision_detection/world_diff.h | 2 +- .../collision_detection_bullet/bullet_integration/basic_types.h | 2 +- .../bullet_integration/bullet_bvh_manager.h | 2 +- .../bullet_integration/bullet_cast_bvh_manager.h | 2 +- .../bullet_integration/bullet_discrete_bvh_manager.h | 2 +- .../bullet_integration/bullet_utils.h | 2 +- .../bullet_integration/contact_checker_common.h | 2 +- .../bullet_integration/ros_bullet_utils.h | 2 +- .../collision_detector_allocator_bullet.h | 2 +- .../collision_detector_bullet_plugin_loader.h | 2 +- .../moveit/collision_detection_bullet/collision_env_bullet.h | 2 +- .../include/moveit/collision_detection_fcl/collision_common.h | 2 +- .../collision_detection_fcl/collision_detector_allocator_fcl.h | 2 +- .../collision_detector_fcl_plugin_loader.h | 2 +- .../include/moveit/collision_detection_fcl/collision_env_fcl.h | 2 +- .../include/moveit/collision_detection_fcl/fcl_compat.h | 2 +- .../collision_distance_field/collision_common_distance_field.h | 2 +- .../collision_detector_allocator_distance_field.h | 2 +- .../collision_detector_allocator_hybrid.h | 2 +- .../collision_distance_field/collision_distance_field_types.h | 2 +- .../collision_distance_field/collision_env_distance_field.h | 2 +- .../moveit/collision_distance_field/collision_env_hybrid.h | 2 +- .../include/moveit/constraint_samplers/constraint_sampler.h | 2 +- .../moveit/constraint_samplers/constraint_sampler_allocator.h | 2 +- .../moveit/constraint_samplers/constraint_sampler_manager.h | 2 +- .../moveit/constraint_samplers/constraint_sampler_tools.h | 2 +- .../moveit/constraint_samplers/default_constraint_samplers.h | 2 +- .../moveit/constraint_samplers/union_constraint_sampler.h | 2 +- .../include/moveit/controller_manager/controller_manager.h | 2 +- .../include/moveit/distance_field/distance_field.h | 2 +- .../include/moveit/distance_field/find_internal_points.h | 2 +- .../include/moveit/distance_field/propagation_distance_field.h | 2 +- .../distance_field/include/moveit/distance_field/voxel_grid.h | 2 +- .../include/moveit/dynamics_solver/dynamics_solver.h | 2 +- moveit_core/exceptions/include/moveit/exceptions/exceptions.h | 2 +- .../include/moveit/kinematic_constraints/kinematic_constraint.h | 2 +- .../include/moveit/kinematic_constraints/utils.h | 2 +- .../include/moveit/kinematics_base/kinematics_base.h | 2 +- .../include/moveit/kinematics_metrics/kinematics_metrics.h | 2 +- moveit_core/macros/include/moveit/macros/class_forward.h | 2 +- moveit_core/macros/include/moveit/macros/console_colors.h | 2 +- moveit_core/macros/include/moveit/macros/declare_ptr.h | 2 +- moveit_core/macros/include/moveit/macros/deprecation.h | 2 +- .../moveit/online_signal_smoothing/acceleration_filter.h | 2 +- .../include/moveit/online_signal_smoothing/butterworth_filter.h | 2 +- .../include/moveit/online_signal_smoothing/ruckig_filter.h | 2 +- .../moveit/online_signal_smoothing/smoothing_base_class.h | 2 +- .../include/moveit/planning_interface/planning_interface.h | 2 +- .../include/moveit/planning_interface/planning_request.h | 2 +- .../moveit/planning_interface/planning_request_adapter.h | 2 +- .../include/moveit/planning_interface/planning_response.h | 2 +- .../moveit/planning_interface/planning_response_adapter.h | 2 +- .../include/moveit/planning_scene/planning_scene.h | 2 +- moveit_core/robot_model/include/moveit/robot_model/aabb.h | 2 +- .../robot_model/include/moveit/robot_model/fixed_joint_model.h | 2 +- .../include/moveit/robot_model/floating_joint_model.h | 2 +- .../robot_model/include/moveit/robot_model/joint_model.h | 2 +- .../robot_model/include/moveit/robot_model/joint_model_group.h | 2 +- moveit_core/robot_model/include/moveit/robot_model/link_model.h | 2 +- .../robot_model/include/moveit/robot_model/planar_joint_model.h | 2 +- .../include/moveit/robot_model/prismatic_joint_model.h | 2 +- .../include/moveit/robot_model/revolute_joint_model.h | 2 +- .../robot_model/include/moveit/robot_model/robot_model.h | 2 +- .../robot_state/include/moveit/robot_state/attached_body.h | 2 +- .../include/moveit/robot_state/cartesian_interpolator.h | 2 +- .../robot_state/include/moveit/robot_state/conversions.h | 2 +- .../robot_state/include/moveit/robot_state/robot_state.h | 2 +- .../include/moveit/robot_trajectory/robot_trajectory.h | 2 +- .../moveit/trajectory_processing/ruckig_traj_smoothing.h | 2 +- .../trajectory_processing/time_optimal_trajectory_generation.h | 2 +- .../moveit/trajectory_processing/time_parameterization.h | 2 +- .../include/moveit/trajectory_processing/trajectory_tools.h | 2 +- moveit_core/transforms/include/moveit/transforms/transforms.h | 2 +- moveit_core/utils/include/moveit/utils/eigen_test_utils.h | 2 +- moveit_core/utils/include/moveit/utils/lexical_casts.h | 2 +- moveit_core/utils/include/moveit/utils/logger.h | 2 +- moveit_core/utils/include/moveit/utils/message_checks.h | 2 +- moveit_core/utils/include/moveit/utils/moveit_error_code.h | 2 +- moveit_core/utils/include/moveit/utils/rclcpp_utils.h | 2 +- moveit_core/utils/include/moveit/utils/robot_model_test_utils.h | 2 +- .../cached_ik_kinematics_plugin-inl.h | 2 +- .../cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h | 2 +- .../moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h | 2 +- .../cached_ik_kinematics_plugin/detail/NearestNeighbors.h | 2 +- .../cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h | 2 +- .../moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h | 2 +- .../include/moveit/kdl_kinematics_plugin/joint_mimic.h | 2 +- .../moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h | 2 +- .../moveit/srv_kinematics_plugin/srv_kinematics_plugin.h | 2 +- .../chomp_interface/include/chomp_interface/chomp_interface.h | 2 +- .../include/chomp_interface/chomp_planning_context.h | 2 +- .../include/chomp_motion_planner/chomp_cost.h | 2 +- .../include/chomp_motion_planner/chomp_optimizer.h | 2 +- .../include/chomp_motion_planner/chomp_parameters.h | 2 +- .../include/chomp_motion_planner/chomp_planner.h | 2 +- .../include/chomp_motion_planner/chomp_trajectory.h | 2 +- .../include/chomp_motion_planner/chomp_utils.h | 2 +- .../include/chomp_motion_planner/multivariate_gaussian.h | 2 +- .../moveit/ompl_interface/detail/constrained_goal_sampler.h | 2 +- .../include/moveit/ompl_interface/detail/constrained_sampler.h | 2 +- .../moveit/ompl_interface/detail/constraint_approximations.h | 2 +- .../include/moveit/ompl_interface/detail/constraints_library.h | 2 +- .../include/moveit/ompl_interface/detail/goal_union.h | 2 +- .../include/moveit/ompl_interface/detail/ompl_constraints.h | 2 +- .../moveit/ompl_interface/detail/projection_evaluators.h | 2 +- .../moveit/ompl_interface/detail/state_validity_checker.h | 2 +- .../moveit/ompl_interface/detail/threadsafe_state_storage.h | 2 +- .../moveit/ompl_interface/model_based_planning_context.h | 2 +- .../include/moveit/ompl_interface/ompl_interface.h | 2 +- .../joint_space/constrained_planning_state_space.h | 2 +- .../joint_space/constrained_planning_state_space_factory.h | 2 +- .../parameterization/joint_space/joint_model_state_space.h | 2 +- .../joint_space/joint_model_state_space_factory.h | 2 +- .../ompl_interface/parameterization/model_based_state_space.h | 2 +- .../parameterization/model_based_state_space_factory.h | 2 +- .../parameterization/work_space/pose_model_state_space.h | 2 +- .../work_space/pose_model_state_space_factory.h | 2 +- .../include/moveit/ompl_interface/planning_context_manager.h | 2 +- .../include/joint_limits_copy/joint_limits.h | 2 +- .../include/joint_limits_copy/joint_limits_rosparam.h | 2 +- .../include/pilz_industrial_motion_planner/capability_names.h | 2 +- .../pilz_industrial_motion_planner/cartesian_trajectory.h | 2 +- .../pilz_industrial_motion_planner/cartesian_trajectory_point.h | 2 +- .../pilz_industrial_motion_planner/command_list_manager.h | 2 +- .../pilz_industrial_motion_planner/joint_limits_aggregator.h | 2 +- .../pilz_industrial_motion_planner/joint_limits_container.h | 2 +- .../pilz_industrial_motion_planner/joint_limits_extension.h | 2 +- .../joint_limits_interface_extension.h | 2 +- .../pilz_industrial_motion_planner/joint_limits_validator.h | 2 +- .../include/pilz_industrial_motion_planner/limits_container.h | 2 +- .../pilz_industrial_motion_planner/move_group_sequence_action.h | 2 +- .../move_group_sequence_service.h | 2 +- .../pilz_industrial_motion_planner/path_circle_generator.h | 2 +- .../pilz_industrial_motion_planner.h | 2 +- .../pilz_industrial_motion_planner/plan_components_builder.h | 2 +- .../pilz_industrial_motion_planner/planning_context_base.h | 2 +- .../pilz_industrial_motion_planner/planning_context_circ.h | 2 +- .../pilz_industrial_motion_planner/planning_context_lin.h | 2 +- .../pilz_industrial_motion_planner/planning_context_loader.h | 2 +- .../planning_context_loader_circ.h | 2 +- .../planning_context_loader_lin.h | 2 +- .../planning_context_loader_ptp.h | 2 +- .../pilz_industrial_motion_planner/planning_context_ptp.h | 2 +- .../pilz_industrial_motion_planner/planning_exceptions.h | 2 +- .../include/pilz_industrial_motion_planner/tip_frame_getter.h | 2 +- .../pilz_industrial_motion_planner/trajectory_blend_request.h | 2 +- .../pilz_industrial_motion_planner/trajectory_blend_response.h | 2 +- .../include/pilz_industrial_motion_planner/trajectory_blender.h | 2 +- .../trajectory_blender_transition_window.h | 2 +- .../pilz_industrial_motion_planner/trajectory_functions.h | 2 +- .../trajectory_generation_exceptions.h | 2 +- .../pilz_industrial_motion_planner/trajectory_generator.h | 2 +- .../pilz_industrial_motion_planner/trajectory_generator_circ.h | 2 +- .../pilz_industrial_motion_planner/trajectory_generator_lin.h | 2 +- .../pilz_industrial_motion_planner/trajectory_generator_ptp.h | 2 +- .../pilz_industrial_motion_planner/velocity_profile_atrap.h | 2 +- .../pilz_industrial_motion_planner_testutils/async_test.h | 2 +- .../include/pilz_industrial_motion_planner_testutils/basecmd.h | 2 +- .../cartesianconfiguration.h | 2 +- .../cartesianpathconstraintsbuilder.h | 2 +- .../include/pilz_industrial_motion_planner_testutils/center.h | 2 +- .../include/pilz_industrial_motion_planner_testutils/checks.h | 2 +- .../include/pilz_industrial_motion_planner_testutils/circ.h | 2 +- .../circ_auxiliary_types.h | 2 +- .../pilz_industrial_motion_planner_testutils/circauxiliary.h | 2 +- .../command_types_typedef.h | 2 +- .../pilz_industrial_motion_planner_testutils/default_values.h | 2 +- .../pilz_industrial_motion_planner_testutils/exception_types.h | 2 +- .../goalconstraintsmsgconvertible.h | 2 +- .../include/pilz_industrial_motion_planner_testutils/gripper.h | 2 +- .../include/pilz_industrial_motion_planner_testutils/interim.h | 2 +- .../jointconfiguration.h | 2 +- .../include/pilz_industrial_motion_planner_testutils/lin.h | 2 +- .../pilz_industrial_motion_planner_testutils/motioncmd.h | 2 +- .../motionplanrequestconvertible.h | 2 +- .../include/pilz_industrial_motion_planner_testutils/ptp.h | 2 +- .../robotconfiguration.h | 2 +- .../robotstatemsgconvertible.h | 2 +- .../include/pilz_industrial_motion_planner_testutils/sequence.h | 2 +- .../pilz_industrial_motion_planner_testutils/testdata_loader.h | 2 +- .../pilz_industrial_motion_planner_testutils/xml_constants.h | 2 +- .../xml_testdata_loader.h | 2 +- .../stomp/include/stomp_moveit/conversion_functions.h | 2 +- moveit_planners/stomp/include/stomp_moveit/cost_functions.h | 2 +- moveit_planners/stomp/include/stomp_moveit/filter_functions.h | 2 +- .../stomp/include/stomp_moveit/math/multivariate_gaussian.h | 2 +- moveit_planners/stomp/include/stomp_moveit/noise_generators.h | 2 +- .../stomp/include/stomp_moveit/stomp_moveit_planning_context.h | 2 +- moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h | 2 +- .../stomp/include/stomp_moveit/trajectory_visualization.h | 2 +- .../include/moveit_ros_control_interface/ControllerHandle.h | 2 +- .../action_based_controller_handle.h | 2 +- .../moveit_simple_controller_manager/empty_controller_handle.h | 2 +- .../follow_joint_trajectory_controller_handle.h | 2 +- .../gripper_controller_handle.h | 2 +- .../include/moveit_py/moveit_py_utils/copy_ros_msg.h | 2 +- .../include/moveit_py/moveit_py_utils/ros_msg_typecasters.h | 2 +- .../benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h | 2 +- .../benchmarks/include/moveit/benchmarks/BenchmarkOptions.h | 2 +- .../include/moveit/global_planner/global_planner_component.h | 2 +- .../include/moveit/global_planner/global_planner_interface.h | 2 +- .../include/moveit/global_planner/moveit_planning_pipeline.h | 2 +- .../moveit/hybrid_planning_manager/hybrid_planning_events.h | 2 +- .../moveit/hybrid_planning_manager/hybrid_planning_manager.h | 2 +- .../moveit/hybrid_planning_manager/planner_logic_interface.h | 2 +- .../planner_logic_plugins/replan_invalidated_trajectory.h | 2 +- .../moveit/planner_logic_plugins/single_plan_execution.h | 2 +- .../moveit/local_constraint_solver_plugins/forward_trajectory.h | 2 +- .../include/moveit/local_planner/feedback_types.h | 2 +- .../moveit/local_planner/local_constraint_solver_interface.h | 2 +- .../include/moveit/local_planner/local_planner_component.h | 2 +- .../moveit/local_planner/trajectory_operator_interface.h | 2 +- .../include/moveit/trajectory_operator_plugins/simple_sampler.h | 2 +- .../move_group/include/moveit/move_group/capability_names.h | 2 +- .../include/moveit/move_group/move_group_capability.h | 2 +- .../move_group/include/moveit/move_group/move_group_context.h | 2 +- .../moveit_servo/include/moveit_servo/collision_monitor.h | 2 +- moveit_ros/moveit_servo/include/moveit_servo/servo.h | 2 +- moveit_ros/moveit_servo/include/moveit_servo/servo_node.h | 2 +- moveit_ros/moveit_servo/include/moveit_servo/utils/command.h | 2 +- moveit_ros/moveit_servo/include/moveit_servo/utils/common.h | 2 +- moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h | 2 +- .../moveit/occupancy_map_monitor/occupancy_map_monitor.h | 2 +- .../occupancy_map_monitor_middleware_handle.h | 2 +- .../moveit/occupancy_map_monitor/occupancy_map_updater.h | 2 +- .../depth_image_octomap_updater/depth_image_octomap_updater.h | 2 +- .../moveit/lazy_free_space_updater/lazy_free_space_updater.h | 2 +- .../include/moveit/mesh_filter/depth_self_filter_nodelet.h | 2 +- .../mesh_filter/include/moveit/mesh_filter/filter_job.h | 2 +- .../perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h | 2 +- .../mesh_filter/include/moveit/mesh_filter/gl_renderer.h | 2 +- .../mesh_filter/include/moveit/mesh_filter/mesh_filter.h | 2 +- .../mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h | 2 +- .../mesh_filter/include/moveit/mesh_filter/sensor_model.h | 2 +- .../include/moveit/mesh_filter/stereo_camera_model.h | 2 +- .../mesh_filter/include/moveit/mesh_filter/transform_provider.h | 2 +- .../include/moveit/point_containment_filter/shape_mask.h | 2 +- .../pointcloud_octomap_updater/pointcloud_octomap_updater.h | 2 +- .../include/moveit/semantic_world/semantic_world.h | 2 +- .../moveit/collision_plugin_loader/collision_plugin_loader.h | 2 +- .../constraint_sampler_manager_loader.h | 2 +- .../moveit/kinematics_plugin_loader/kinematics_plugin_loader.h | 2 +- .../planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h | 2 +- .../moveit_cpp/include/moveit/moveit_cpp/planning_component.h | 2 +- .../include/moveit/plan_execution/plan_execution.h | 2 +- .../include/moveit/plan_execution/plan_representation.h | 2 +- .../include/moveit/planning_pipeline/planning_pipeline.h | 2 +- .../planning_pipeline_interfaces/plan_responses_container.h | 2 +- .../planning_pipeline_interfaces/planning_pipeline_interfaces.h | 2 +- .../planning_pipeline_interfaces/solution_selection_functions.h | 2 +- .../planning_pipeline_interfaces/stopping_criterion_functions.h | 2 +- .../moveit/planning_scene_monitor/current_state_monitor.h | 2 +- .../current_state_monitor_middleware_handle.h | 2 +- .../moveit/planning_scene_monitor/planning_scene_monitor.h | 2 +- .../include/moveit/planning_scene_monitor/trajectory_monitor.h | 2 +- .../trajectory_monitor_middleware_handle.h | 2 +- .../planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h | 2 +- .../include/moveit/rdf_loader/synchronized_string_parameter.h | 2 +- .../include/moveit/robot_model_loader/robot_model_loader.h | 2 +- .../trajectory_execution_manager/trajectory_execution_manager.h | 2 +- .../moveit/common_planning_interface_objects/common_objects.h | 2 +- .../include/moveit/move_group_interface/move_group_interface.h | 2 +- .../moveit/planning_scene_interface/planning_scene_interface.h | 2 +- .../include/moveit/robot_interaction/interaction.h | 2 +- .../include/moveit/robot_interaction/interaction_handler.h | 2 +- .../moveit/robot_interaction/interactive_marker_helpers.h | 2 +- .../include/moveit/robot_interaction/kinematic_options.h | 2 +- .../include/moveit/robot_interaction/kinematic_options_map.h | 2 +- .../include/moveit/robot_interaction/locked_robot_state.h | 2 +- .../include/moveit/robot_interaction/robot_interaction.h | 2 +- moveit_ros/tests/include/parameter_name_list.h | 2 +- .../include/moveit/trajectory_cache/trajectory_cache.h | 2 +- .../motion_planning_rviz_plugin/interactive_marker_display.h | 2 +- .../motion_planning_rviz_plugin/motion_planning_display.h | 2 +- .../moveit/motion_planning_rviz_plugin/motion_planning_frame.h | 2 +- .../motion_planning_frame_joints_widget.h | 2 +- .../motion_planning_rviz_plugin/motion_planning_param_widget.h | 2 +- .../moveit/planning_scene_rviz_plugin/background_processing.h | 2 +- .../moveit/planning_scene_rviz_plugin/planning_scene_display.h | 2 +- .../moveit/robot_state_rviz_plugin/robot_state_display.h | 2 +- .../include/moveit/rviz_plugin_render_tools/octomap_render.h | 2 +- .../moveit/rviz_plugin_render_tools/planning_link_updater.h | 2 +- .../moveit/rviz_plugin_render_tools/planning_scene_render.h | 2 +- .../include/moveit/rviz_plugin_render_tools/render_shapes.h | 2 +- .../moveit/rviz_plugin_render_tools/robot_state_visualization.h | 2 +- .../include/moveit/rviz_plugin_render_tools/trajectory_panel.h | 2 +- .../moveit/rviz_plugin_render_tools/trajectory_visualization.h | 2 +- .../rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h | 2 +- .../include/moveit/trajectory_rviz_plugin/trajectory_display.h | 2 +- .../warehouse/include/moveit/warehouse/constraints_storage.h | 2 +- .../warehouse/include/moveit/warehouse/moveit_message_storage.h | 2 +- .../warehouse/include/moveit/warehouse/planning_scene_storage.h | 2 +- .../include/moveit/warehouse/planning_scene_world_storage.h | 2 +- moveit_ros/warehouse/include/moveit/warehouse/state_storage.h | 2 +- .../include/moveit/warehouse/trajectory_constraints_storage.h | 2 +- .../warehouse/include/moveit/warehouse/warehouse_connector.h | 2 +- .../include/moveit_setup_app_plugins/launch_bundle.h | 2 +- .../include/moveit_setup_app_plugins/launches.h | 2 +- .../include/moveit_setup_app_plugins/launches_config.h | 2 +- .../include/moveit_setup_app_plugins/launches_widget.h | 2 +- .../include/moveit_setup_app_plugins/perception.h | 2 +- .../include/moveit_setup_app_plugins/perception_config.h | 2 +- .../include/moveit_setup_app_plugins/perception_widget.h | 2 +- .../include/moveit_setup_assistant/navigation_widget.h | 2 +- .../include/moveit_setup_assistant/setup_assistant_widget.h | 2 +- .../include/moveit_setup_controllers/control_xacro_config.h | 2 +- .../include/moveit_setup_controllers/controller_edit_widget.h | 2 +- .../include/moveit_setup_controllers/controllers.h | 2 +- .../include/moveit_setup_controllers/controllers_config.h | 2 +- .../include/moveit_setup_controllers/controllers_widget.h | 2 +- .../include/moveit_setup_controllers/included_xacro_config.h | 2 +- .../include/moveit_setup_controllers/modified_urdf_config.h | 2 +- .../include/moveit_setup_controllers/moveit_controllers.h | 2 +- .../moveit_setup_controllers/moveit_controllers_config.h | 2 +- .../include/moveit_setup_controllers/ros2_controllers.h | 2 +- .../include/moveit_setup_controllers/ros2_controllers_config.h | 2 +- .../include/moveit_setup_controllers/urdf_modifications.h | 2 +- .../moveit_setup_controllers/urdf_modifications_widget.h | 2 +- .../include/moveit_setup_core_plugins/author_information.h | 2 +- .../moveit_setup_core_plugins/author_information_widget.h | 2 +- .../include/moveit_setup_core_plugins/configuration_files.h | 2 +- .../moveit_setup_core_plugins/configuration_files_widget.h | 2 +- .../include/moveit_setup_core_plugins/start_screen.h | 2 +- .../include/moveit_setup_core_plugins/start_screen_widget.h | 2 +- .../include/moveit_setup_framework/config.h | 2 +- .../moveit_setup_framework/data/package_settings_config.h | 2 +- .../include/moveit_setup_framework/data/srdf_config.h | 2 +- .../include/moveit_setup_framework/data/urdf_config.h | 2 +- .../include/moveit_setup_framework/data_warehouse.h | 2 +- .../include/moveit_setup_framework/generated_file.h | 2 +- .../include/moveit_setup_framework/generated_time.h | 2 +- .../include/moveit_setup_framework/qt/double_list_widget.h | 2 +- .../include/moveit_setup_framework/qt/helper_widgets.h | 2 +- .../include/moveit_setup_framework/qt/rviz_panel.h | 2 +- .../include/moveit_setup_framework/qt/setup_step_widget.h | 2 +- .../include/moveit_setup_framework/qt/xml_syntax_highlighter.h | 2 +- .../include/moveit_setup_framework/setup_step.h | 2 +- .../include/moveit_setup_framework/templates.h | 2 +- .../include/moveit_setup_framework/testing_utils.h | 2 +- .../include/moveit_setup_framework/utilities.h | 2 +- .../include/moveit_setup_simulation/simulation.h | 2 +- .../include/moveit_setup_simulation/simulation_widget.h | 2 +- .../include/moveit_setup_srdf_plugins/collision_linear_model.h | 2 +- .../include/moveit_setup_srdf_plugins/collision_matrix_model.h | 2 +- .../moveit_setup_srdf_plugins/compute_default_collisions.h | 2 +- .../include/moveit_setup_srdf_plugins/default_collisions.h | 2 +- .../moveit_setup_srdf_plugins/default_collisions_widget.h | 2 +- .../include/moveit_setup_srdf_plugins/end_effectors.h | 2 +- .../include/moveit_setup_srdf_plugins/end_effectors_widget.h | 2 +- .../include/moveit_setup_srdf_plugins/group_edit_widget.h | 2 +- .../include/moveit_setup_srdf_plugins/group_meta_config.h | 2 +- .../include/moveit_setup_srdf_plugins/kinematic_chain_widget.h | 2 +- .../include/moveit_setup_srdf_plugins/passive_joints.h | 2 +- .../include/moveit_setup_srdf_plugins/passive_joints_widget.h | 2 +- .../include/moveit_setup_srdf_plugins/planning_groups.h | 2 +- .../include/moveit_setup_srdf_plugins/planning_groups_widget.h | 2 +- .../include/moveit_setup_srdf_plugins/robot_poses.h | 2 +- .../include/moveit_setup_srdf_plugins/robot_poses_widget.h | 2 +- .../include/moveit_setup_srdf_plugins/rotated_header_view.h | 2 +- .../include/moveit_setup_srdf_plugins/srdf_step.h | 2 +- .../include/moveit_setup_srdf_plugins/virtual_joints.h | 2 +- .../include/moveit_setup_srdf_plugins/virtual_joints_widget.h | 2 +- 376 files changed, 376 insertions(+), 376 deletions(-) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h index 32788fa020..e4612075c4 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h index 14ad0c66a2..5e170761d9 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h index cd15aff7f5..ec90518579 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h index 5cbb180837..a4603a6684 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h index 9f595cb590..a0a8620fae 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h index dc2be05a21..7398244de1 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h index cc06a592ca..cce836826d 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h index e3a7410be7..2008f2d6f1 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h index f4cc4c71cb..16a7cbae83 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h index 258eadba21..355b7f21d1 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h b/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h index 8b690149f8..287e5378ab 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h index 2174eae909..196b0a5319 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h index 653fa8358a..c5cc2355eb 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/world.h b/moveit_core/collision_detection/include/moveit/collision_detection/world.h index 363fabac62..6ae557dc63 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/world.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/world.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h b/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h index fa9275490e..e3b36bc100 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h index 9f27078b55..f35acaa28e 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h @@ -22,6 +22,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h index fbf89b664b..cfda30bef9 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h @@ -35,6 +35,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h index a35972e0df..8956a9540a 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h @@ -35,6 +35,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h index f26718366e..86ce5f70a2 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h @@ -35,6 +35,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h index de55dc4cc3..1b598cd41c 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h index 0f512eece7..3b37237188 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h @@ -22,6 +22,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h index 70c2ff3211..714bf2c5c1 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h @@ -22,6 +22,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h index 1c5ebb83c6..5b94987544 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h index 3f751e56b9..9c4fbfa748 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h index 109ca5e612..ea969018d3 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h index f745818943..30f45c8648 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h index 10fe6917b7..5587a69563 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h index 88020bd96f..87f2e8df55 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h index d6bf6c7a96..97efefe834 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h index 334b6e6f22..82b8b9dcac 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h index a402e27511..76d3390115 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h index 2edaf14365..f0d43d75cc 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h index 06476f376b..47dcc1c38f 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h index b2bc6657a7..4374597bff 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h index ff51c5c821..79ccf9a654 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h index 4fb0a539f9..9635a377e1 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h index 87b5930d74..ec74f6b91a 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h index a335db3f44..d80a16739f 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h index b3085622eb..e41302158b 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h index 3a8ea727a0..e030f26a22 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h index f14d98795e..dbf893f407 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h index 4d36a6b68d..02337e72c9 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h b/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h index 900fd208bc..905d928455 100644 --- a/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h +++ b/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/distance_field/include/moveit/distance_field/distance_field.h b/moveit_core/distance_field/include/moveit/distance_field/distance_field.h index 4ffefecc07..7b54b5eba0 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/distance_field.h +++ b/moveit_core/distance_field/include/moveit/distance_field/distance_field.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h b/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h index fa80414aaa..9942543c46 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h +++ b/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h b/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h index a42ad2f184..1413557278 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h +++ b/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h b/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h index 94c8c2e415..2a0435fe16 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h +++ b/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h b/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h index 21f7d24b23..e0ddc6ee20 100644 --- a/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h +++ b/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/exceptions/include/moveit/exceptions/exceptions.h b/moveit_core/exceptions/include/moveit/exceptions/exceptions.h index 46d7f83af2..8647d73f11 100644 --- a/moveit_core/exceptions/include/moveit/exceptions/exceptions.h +++ b/moveit_core/exceptions/include/moveit/exceptions/exceptions.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h index b43d41bad0..73cf72897b 100644 --- a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h +++ b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h index 7a23af9225..700e685583 100644 --- a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h +++ b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h index b9d6469aa6..2f6850255c 100644 --- a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h +++ b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h b/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h index b107377001..ea5bbd2005 100644 --- a/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h +++ b/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/macros/include/moveit/macros/class_forward.h b/moveit_core/macros/include/moveit/macros/class_forward.h index 31191ea2ab..78901b394b 100644 --- a/moveit_core/macros/include/moveit/macros/class_forward.h +++ b/moveit_core/macros/include/moveit/macros/class_forward.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/macros/include/moveit/macros/console_colors.h b/moveit_core/macros/include/moveit/macros/console_colors.h index 88d2602fa2..713c954720 100644 --- a/moveit_core/macros/include/moveit/macros/console_colors.h +++ b/moveit_core/macros/include/moveit/macros/console_colors.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/macros/include/moveit/macros/declare_ptr.h b/moveit_core/macros/include/moveit/macros/declare_ptr.h index 29a2e84500..f80d6d0057 100644 --- a/moveit_core/macros/include/moveit/macros/declare_ptr.h +++ b/moveit_core/macros/include/moveit/macros/declare_ptr.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/macros/include/moveit/macros/deprecation.h b/moveit_core/macros/include/moveit/macros/deprecation.h index 973eef48ac..53e9533ac5 100644 --- a/moveit_core/macros/include/moveit/macros/deprecation.h +++ b/moveit_core/macros/include/moveit/macros/deprecation.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h index b0df2730d5..eb118c706d 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h @@ -74,6 +74,6 @@ c --------x--- v | #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h index d69bbdc330..07dcb3ae3d 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h index 1712a8f2a8..3ad48b6daf 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h @@ -40,6 +40,6 @@ Description: Applies jerk/acceleration/velocity limits to online motion commands #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h index df2317c75a..46e83a6937 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h @@ -40,6 +40,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h index a1a2117cf6..2c213c3a19 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h index 796433821f..1fcfe02957 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h index 94225d92e5..bca74f5256 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h @@ -40,6 +40,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h index 6b07a7acec..53770b38a5 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h index b26ff6cf0b..4d8ab1c948 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h index 796a096106..93cc4ffebe 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/aabb.h b/moveit_core/robot_model/include/moveit/robot_model/aabb.h index e468978776..c959fe3f64 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/aabb.h +++ b/moveit_core/robot_model/include/moveit/robot_model/aabb.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h index 44a056b947..e672ed4bf6 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h index 4c7f5c5edd..f9e63b0923 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/joint_model.h index 8acfaf27e8..fa2c4ccdb9 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/joint_model.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h index 1810fc35c0..678a416462 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h +++ b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/link_model.h b/moveit_core/robot_model/include/moveit/robot_model/link_model.h index 0e795d0663..481ce4b8c5 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/link_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/link_model.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h index 3e5ab7f4d4..f53cefcfc4 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h index 0c481c3b26..f86748305c 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h index 059c7b25ae..2c90b6f926 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h index f5b94e1e8e..97adcf6b5e 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/robot_state/include/moveit/robot_state/attached_body.h b/moveit_core/robot_state/include/moveit/robot_state/attached_body.h index 5cf4a30a1f..26fae9b016 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/attached_body.h +++ b/moveit_core/robot_state/include/moveit/robot_state/attached_body.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h b/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h index 996f6d29b9..8cd6a999d9 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h +++ b/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h @@ -40,6 +40,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/robot_state/include/moveit/robot_state/conversions.h b/moveit_core/robot_state/include/moveit/robot_state/conversions.h index 5d3bd8812e..676667dba5 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/conversions.h +++ b/moveit_core/robot_state/include/moveit/robot_state/conversions.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h index 06d33c1e71..398b96a46e 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h +++ b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h index c19a1893c0..7adef007c3 100644 --- a/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h +++ b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h index 5d1b609b2a..19b3b0c436 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h @@ -37,6 +37,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h index b5a2566778..874d7256cc 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h @@ -40,6 +40,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h index b10e52cef2..ce63309901 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h @@ -2,6 +2,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h index 4e922ad63a..3da16de211 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/transforms/include/moveit/transforms/transforms.h b/moveit_core/transforms/include/moveit/transforms/transforms.h index 53ac9b0ab5..400672a775 100644 --- a/moveit_core/transforms/include/moveit/transforms/transforms.h +++ b/moveit_core/transforms/include/moveit/transforms/transforms.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/utils/include/moveit/utils/eigen_test_utils.h b/moveit_core/utils/include/moveit/utils/eigen_test_utils.h index cd680b07ce..6edc813391 100644 --- a/moveit_core/utils/include/moveit/utils/eigen_test_utils.h +++ b/moveit_core/utils/include/moveit/utils/eigen_test_utils.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/utils/include/moveit/utils/lexical_casts.h b/moveit_core/utils/include/moveit/utils/lexical_casts.h index 0c9b528cb2..25e2c9ae3e 100644 --- a/moveit_core/utils/include/moveit/utils/lexical_casts.h +++ b/moveit_core/utils/include/moveit/utils/lexical_casts.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/utils/include/moveit/utils/logger.h b/moveit_core/utils/include/moveit/utils/logger.h index 3109573f57..0cc31ac22a 100644 --- a/moveit_core/utils/include/moveit/utils/logger.h +++ b/moveit_core/utils/include/moveit/utils/logger.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/utils/include/moveit/utils/message_checks.h b/moveit_core/utils/include/moveit/utils/message_checks.h index 137fcdb61e..2f80182981 100644 --- a/moveit_core/utils/include/moveit/utils/message_checks.h +++ b/moveit_core/utils/include/moveit/utils/message_checks.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/utils/include/moveit/utils/moveit_error_code.h b/moveit_core/utils/include/moveit/utils/moveit_error_code.h index fd822911d1..293751a2b4 100644 --- a/moveit_core/utils/include/moveit/utils/moveit_error_code.h +++ b/moveit_core/utils/include/moveit/utils/moveit_error_code.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/utils/include/moveit/utils/rclcpp_utils.h b/moveit_core/utils/include/moveit/utils/rclcpp_utils.h index 4c278c3f7e..84bb3ad038 100644 --- a/moveit_core/utils/include/moveit/utils/rclcpp_utils.h +++ b/moveit_core/utils/include/moveit/utils/rclcpp_utils.h @@ -29,6 +29,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h b/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h index 700deef054..7487bc783b 100644 --- a/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h +++ b/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h index 59660a0413..060faaee2c 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h index b94b1c7141..ff7d0df1a1 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h index a09f8dd9e8..1633372a05 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h @@ -40,6 +40,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h index 3bfe208998..34c074bf61 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h @@ -40,6 +40,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h index 54986b1bfd..3978ba0e31 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h @@ -40,6 +40,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h index 4e49b63e3d..097acec5ad 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h +++ b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h @@ -27,6 +27,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h index 7dc1dc9359..eedf098569 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h +++ b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h index 17e49299bc..87f914d4e1 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h +++ b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h b/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h index 379c9ea58f..18816e3829 100644 --- a/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h +++ b/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h @@ -43,6 +43,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h index 1e8810c7e4..858adc9f14 100644 --- a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h +++ b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h index bc6b3260d1..eac76c8665 100644 --- a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h +++ b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h index b4cfb262f4..ef40b9e774 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h index 876f704e0d..ebf7e4c16a 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h index 18159fb926..12d84dfee0 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h index b8470be276..2552ff7f1f 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h index a474237f28..8e453e54c1 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h index b5083d5704..8bb66984c4 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h index 91c82c71f6..5bb1e6a327 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h index c5d4133de9..8fec013598 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h index 74b74a47b5..cf7db621e4 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h index 8aea86a2c1..d76b102f17 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h index 7b1e5352ec..4104cf0725 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h index 47b5e692ae..de8b8f9c16 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h index 4a794a0a46..58e60dda2c 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h index d571345b32..d76fdacde8 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h index 5ba2399fde..65cb13ec64 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h @@ -49,6 +49,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h index d23d0a67be..24b973f15e 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h index 3be8a37b08..4e6bdbbf3b 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h index c576d9ddf8..6aa8f78b29 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h index 75f8bffe40..46403ae15d 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h index dade98b081..89632d608c 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h index b18552862d..a01838fcef 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h index ecc28bfbb1..215e60cedb 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h index 8ac2f9c7b6..e0848378a3 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h index e2e60afe93..4538ac92d1 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h index 382f25f978..b5e6e3efae 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h index 19f9959391..5674788016 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h index 8c33369f29..da8b5383e3 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h index c5309163d8..5dbce8ff1b 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h @@ -18,6 +18,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h index fa448448d7..706c468416 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h @@ -18,6 +18,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h index e1b4ada1b0..a04d3ee9b8 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h index e5406d26ab..a0b47a352f 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h index f32893c680..bfa545456d 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h index 06a9998411..2f72ccea1d 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h index 5e02810d0f..45f206765a 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h index b194892de2..fe677543c5 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h index e71ceedf11..b7c721bf21 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h index 24e0a746dd..725ed99a03 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h index d517e9848b..0f92f6c763 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h index d3c90a4dd0..693fe066c7 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h index 8a00a0b90a..9455bf4e0c 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h index 01dfba2c00..4e0f49d996 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h index b574860af5..d154ecfdc7 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h index 76008b213d..57c423e66d 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h index 559042c9ab..e8019d19fc 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h index b0d4f87c9f..7d3b10d693 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h index 11a2631153..8165f591e7 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h index ec5e3f093c..1264a93057 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h index 69e4a4999f..c45a824c75 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h index 03e4fc1785..cf82c81423 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h index ea860edca1..8f2d763fa9 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h index f6cbed2a3c..6f75c2cb47 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h index 4df443aad7..17f50bccde 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h index ba5a6392d9..54ab569352 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h index cb048deee8..caeadfce7a 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h index 142da2e4f3..ff8a65f497 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h index b6568bd44f..cef5473190 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h index 11dd9c87f5..2617c0872a 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h index b92c92825c..cb6b210544 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h index 876fb40906..ef4d462c3f 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h index f5c2d14d73..876f25b2f6 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h index 8e81e36531..7e6e9b6986 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h index 6eb333780e..737e2d0f85 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h index eb4b923f0a..f316df3e42 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h index 04e276ad4d..515ec9d763 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h index eb63347321..8d80cb50df 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h index 6800c97b01..61ff4fb861 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h @@ -18,6 +18,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h index 53403a5cf9..d3ca68b498 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h index a99a219943..be4726a356 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h index b8aa4aeb8e..d49fbb5d3a 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h index a0a15f852a..152ad9a40d 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h index b7ca93b9fe..f3a4b4f1c6 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h index d6bcc82af2..8c5eb215da 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h index e4036f47f5..1c963ea1a6 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h index dc414d15b1..a2366ead6c 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h index c19c1b34c8..3ab110c526 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h index 1a7b6f3b14..9d5db58189 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h index 2e2546c62d..c7c3243824 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h index 6b2f5ff682..4e272ce40f 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h index 780afcc42b..42b287c9b1 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h index bf88bcc041..2d25069723 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h index 513808cda5..6609b47e87 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h index 355c27c03a..59aac2deb0 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h index a95e7ad5d8..b6846e20ca 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h index d3ede32789..808759cfba 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h index 4ca3e49d09..5806d8e535 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h index b7e064e6b0..eab5c7d390 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h index 1a74c4b9e0..0cec32f96a 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h index f7a5aac8cb..cd6c86f0e9 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h index 090fbddda7..6b9d3645e4 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h index 63849c4fa2..cb3b2a5a7f 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h index b3d05d6816..ff9799c6ee 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h b/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h index 3aa2acba49..6d35d0ce39 100644 --- a/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h +++ b/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/stomp/include/stomp_moveit/cost_functions.h b/moveit_planners/stomp/include/stomp_moveit/cost_functions.h index 82855dcb0d..d9514ca858 100644 --- a/moveit_planners/stomp/include/stomp_moveit/cost_functions.h +++ b/moveit_planners/stomp/include/stomp_moveit/cost_functions.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/stomp/include/stomp_moveit/filter_functions.h b/moveit_planners/stomp/include/stomp_moveit/filter_functions.h index a9087d42ad..304bac63d3 100644 --- a/moveit_planners/stomp/include/stomp_moveit/filter_functions.h +++ b/moveit_planners/stomp/include/stomp_moveit/filter_functions.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h b/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h index 65d7826583..7d3c63a4d7 100644 --- a/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h +++ b/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/stomp/include/stomp_moveit/noise_generators.h b/moveit_planners/stomp/include/stomp_moveit/noise_generators.h index 04b88428f9..ffa1a8e0f4 100644 --- a/moveit_planners/stomp/include/stomp_moveit/noise_generators.h +++ b/moveit_planners/stomp/include/stomp_moveit/noise_generators.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h index e85568bde4..d1a43ad9b5 100644 --- a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h +++ b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h index adc55d8746..3d84986024 100644 --- a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h +++ b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h @@ -56,6 +56,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h b/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h index bf48fa27c3..e072e61c2d 100644 --- a/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h +++ b/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h b/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h index 7e61a64424..bb7ba51126 100644 --- a/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h +++ b/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h index 8283634ece..4ed45aac84 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h index e52a9cd1f3..b7baf0df16 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h index aba78df9fd..9b5037d822 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h index bf54bfe6eb..6152239752 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h index 04b6f9e73b..8c9baa1fe6 100644 --- a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h +++ b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h index e40b0f9d49..20a3bcd65d 100644 --- a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h +++ b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h index 87724c3bc9..6d7f157c81 100644 --- a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h +++ b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h index 4496cb2cb5..a0235870b2 100644 --- a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h +++ b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h index 6099242c3b..75cf064de7 100644 --- a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h +++ b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h @@ -40,6 +40,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h index 04ab97f3b3..fc98b4b056 100644 --- a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h +++ b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h b/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h index ed299a6382..ec6b42c5d0 100644 --- a/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h +++ b/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h index e0cc08fa9b..7cc4256faf 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h @@ -39,6 +39,6 @@ */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h index cc12500b15..0c64d5bf4c 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h @@ -40,6 +40,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h index 1bac9b1d93..d52dfc06ee 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h @@ -40,6 +40,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h index 8db3475151..56598bce51 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h @@ -42,6 +42,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h index 72e257917a..f81586a098 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h b/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h index 0990d826e5..c5ffee6a8f 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h +++ b/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h @@ -42,6 +42,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h index cb4c236ded..912dea86ff 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h index f989d710f6..f9cf7bd1b6 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h @@ -40,6 +40,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h index 24da0a6a9f..a9f4bc8a69 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h index 6e7ff5be29..db19c89a08 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h @@ -40,6 +40,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h b/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h index 2e22ae6920..f99263c98a 100644 --- a/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h +++ b/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h @@ -42,6 +42,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/move_group/include/moveit/move_group/capability_names.h b/moveit_ros/move_group/include/moveit/move_group/capability_names.h index 57de83608a..1a4b5dd9d1 100644 --- a/moveit_ros/move_group/include/moveit/move_group/capability_names.h +++ b/moveit_ros/move_group/include/moveit/move_group/capability_names.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h b/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h index 59128f038c..3cb8f6f981 100644 --- a/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h +++ b/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/move_group/include/moveit/move_group/move_group_context.h b/moveit_ros/move_group/include/moveit/move_group/move_group_context.h index 80ba82e060..ae51f9449e 100644 --- a/moveit_ros/move_group/include/moveit/move_group/move_group_context.h +++ b/moveit_ros/move_group/include/moveit/move_group/move_group_context.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h b/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h index 83cf6350c9..cf0f345a3e 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h @@ -43,6 +43,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/servo.h b/moveit_ros/moveit_servo/include/moveit_servo/servo.h index dd4afc5f1a..54230ef180 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/servo.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/servo.h @@ -43,6 +43,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h b/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h index a645dae89c..a0cf4ac37d 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h @@ -43,6 +43,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h b/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h index 4c5850788a..4a8c3f4d97 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h @@ -43,6 +43,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h b/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h index d94dfebc91..460c47a3f3 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h @@ -43,6 +43,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h b/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h index 18aa3ae3fb..78376498db 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h @@ -43,6 +43,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h index 998c95c996..8f10b946d5 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h index c832e0a2b3..331285a793 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h index da169c926e..4e6036defe 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h b/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h index e1eb7ee74b..8ab969aa8a 100644 --- a/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h +++ b/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h b/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h index 2014030a33..91d58f6a12 100644 --- a/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h +++ b/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h index 946e610958..f43b49e58e 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h index 6705905119..0e22339941 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h index d3f03044f8..1ded5abd9e 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h index d8e964cbc1..c71bf3e530 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h index 8491e1031e..5e2bef80eb 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h index dac4ce8143..9ced6b4634 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h index 36eb2bbfbe..ce9716f7f0 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h index 84f362a4f6..986209a7ac 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h index 7975ea5384..2bc38892f7 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h b/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h index 3d5f11bfa1..9306e04440 100644 --- a/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h +++ b/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h b/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h index e078edde8c..5f6eacc9d1 100644 --- a/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h +++ b/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h index 97dea4c66a..39391a7ad0 100644 --- a/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h +++ b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h b/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h index 10867ef3d5..a33b176404 100644 --- a/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h +++ b/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h b/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h index 6c7259dce7..b3a388ecb2 100644 --- a/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h +++ b/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h b/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h index a9803a7726..d897dafe26 100644 --- a/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h +++ b/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h index 52be4c198b..1ea63e98ac 100644 --- a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h +++ b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h index 6c089c3a4b..1d633e7acd 100644 --- a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h +++ b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h index e3f62fb566..49115751d4 100644 --- a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h +++ b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h index 05b1af9659..0e9fb48650 100644 --- a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h +++ b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h index 7106db6d10..ba314e74c9 100644 --- a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h +++ b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h index 5ab0fa0643..363ca4ad34 100644 --- a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h index e797a51496..7fe30fc6a6 100644 --- a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h index 1ab3c90ff9..2c4ecb6fd3 100644 --- a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h index d5607b3f39..117337b8eb 100644 --- a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h index 2e7bb4f87b..11835d6a51 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h index 515f7c4aaf..85cc67739d 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h index b9ea60230c..257d2f6965 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h index 4494a22fd3..2a40188131 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h index 20fc112e29..c425308290 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h index f1172ccb2d..c34cc1559b 100644 --- a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h +++ b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h index 24969ed02e..954132d6f1 100644 --- a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h +++ b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h b/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h index 6e826ee618..d7e4795055 100644 --- a/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h +++ b/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h index 0a1863d34e..68546f35ef 100644 --- a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h +++ b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h b/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h index 2367e00a5b..09ea5cf002 100644 --- a/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h +++ b/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h index 99547ced31..cdd2780ee1 100644 --- a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h +++ b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h b/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h index fc014269d9..4e3f630a63 100644 --- a/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h +++ b/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h index 11f7631883..9bf4b94a41 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h index dd16a14ff0..c3b89672ba 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h index e186be35e7..16d375a33a 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h index bc3979c334..fd78edf07b 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h index e802e3c63f..e3e07515d2 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h index b786fd5ad4..32a954c61b 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h index 2a6ff0236a..637b67a729 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/tests/include/parameter_name_list.h b/moveit_ros/tests/include/parameter_name_list.h index 2bc307da12..6516fb09da 100644 --- a/moveit_ros/tests/include/parameter_name_list.h +++ b/moveit_ros/tests/include/parameter_name_list.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h b/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h index da046322d6..8b02dcd505 100644 --- a/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h +++ b/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h @@ -21,6 +21,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h index 9c5a0d8d51..2894eadfc9 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h @@ -37,6 +37,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h index cd23d28c26..3c61af21a1 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h index c7ee73240f..55a0b5d7d9 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h index b8eb29431e..24e6233563 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h index 62500a8220..bd6d4be4c5 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h index 6251771f46..0a97984066 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h index 4489c97db7..2e348c235c 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h b/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h index 0223608580..571595bf08 100644 --- a/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h +++ b/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h index f0ec0a9e04..0133c0f163 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h index 0fa1d1a7e4..5d0d9c6a33 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h index 19b0d68dc7..8cdaec5077 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h index 7eecb64aae..0bad8128ce 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h index 114e1361cb..20514b94a3 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h index 49e90558eb..a7db7d43d0 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h index 32a4f4f734..11a861fea0 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h index c3acb69a62..1c3d31eaca 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h @@ -31,6 +31,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h b/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h index 5b07a99568..3df684d154 100644 --- a/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h +++ b/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h @@ -40,6 +40,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h index 438e342a3d..66cc4a96d0 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h index c7e27ebf39..d14481fd90 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h index b34bdba411..6dc98764e2 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h index b56789341b..3ac8369c6d 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h index 1a547f3f3c..563758de8a 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h index e88c776cb4..fe52f872ea 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h b/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h index 2fd3c2c72b..1b1f57cf6c 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h index 7e4aa488b7..13737e29af 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h index e9fbf96a8c..06061aa2a3 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h index d6d0a32ac8..80ab7fee28 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h index dbce78db54..aa8daa862c 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h index ecc43898c6..6242b5946f 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h index 674fe4135c..57a4362be1 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h index 5a860a983b..c9d7a3e5f5 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h @@ -37,6 +37,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h index 5c2d2cb551..93175b537a 100644 --- a/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h +++ b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h index a0e51ad1ed..4cf63e798f 100644 --- a/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h +++ b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h index ed33c57b8a..4033824cb0 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h index f71f7f921f..6ffb6e6d27 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h @@ -37,6 +37,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h index 9ada360418..bbe9b8cbda 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h index abc433642e..787dda97c8 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h index 1747028628..41805e75a7 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h @@ -37,6 +37,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h index 0f279178bf..f023c132dc 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h index 673fd16e33..4da6d81beb 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h index fa333b191b..4bc238fae3 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h index 84a9adfc56..58b45343bf 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h index 6219447841..decc74ea31 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h index be7893a5fd..9dd78d546b 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h index 92d6d79ca3..67ad805a8e 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h index 131bdfc222..2459b1ffbb 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h index 8bd25faa22..51fd0f784e 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h index 7a776e0302..e299bc0d5f 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h index 2530c6dacf..db1d267c88 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h index 7ef7ca3794..68dd34e168 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h index 8b0fe02c27..3bd213012a 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h index 8ea6c9b753..246b8f92a9 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h index d89217b948..45fffa44e1 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h index 236f5befe4..732b71cb00 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h index f0bc016767..d628c237a9 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h index c811e7e0ee..a9afd2217e 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h index 2bb1db533e..536d028e1b 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h @@ -44,6 +44,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h index c170ec6efd..76db21c297 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h index 05431a674b..78145f3d36 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h index 79927f2725..e6e1c55ce4 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h index c5370b4725..e416e09207 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h index 523872683e..db025cfed1 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h index 6892c15540..7a2c6df02c 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h index 5ded47360a..6160ade9af 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h index 5d9694c2ca..66ee7e8e2e 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h index f5d15dd479..ec12c2259b 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h index c79574db2f..4dc2b959a1 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h index fc03d0a9bc..c3467f86a0 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h index e99c122d1c..201201f05a 100644 --- a/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h +++ b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h index 155740b1fb..bbed9bb99e 100644 --- a/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h +++ b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h @@ -37,6 +37,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h index 9820974bc9..02142729e2 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h index f47ed4adac..62714ae047 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h index 19effe012e..11f0334f2f 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h index a378ebb7a2..5c93cc13c0 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h index 5aac2d9346..2e02d330fe 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h index 1b8f537562..71ffae597f 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h index 0c6b0b3881..6005cbb58e 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h index 16875b3104..46223fbcaa 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h index 7367dd60f1..41d953fead 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h index 246da3d7c3..a42cdb850c 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h index 67a2f10b36..77699ccf93 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h index 02cc1ad029..0a866ad18e 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h index d53ecfa980..c24e2f1ba4 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h index c993cd81cb..dad0658950 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h index a53241e51b..d013296060 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h index cbbd6d8ce3..73bfa724b7 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h index abc715d8ba..f4481ca147 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h index 9d9d2554bb..dc8a162e20 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h index 95d18097d0..08d2ec022f 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h index cd7f9332cb..bec377b4e8 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +/* #pragma message(".h header is obsolete. Please use the .hpp") #include From 4d8bdf11ec36fa24dfe1e0146972275ca04268fb Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Thu, 21 Nov 2024 22:33:00 +0000 Subject: [PATCH 43/53] Fixes script comment --- .../allvalid/collision_detector_allocator_allvalid.h | 6 +++--- .../collision_detection/allvalid/collision_env_allvalid.h | 6 +++--- .../include/moveit/collision_detection/collision_common.h | 6 +++--- .../collision_detection/collision_detector_allocator.h | 6 +++--- .../include/moveit/collision_detection/collision_env.h | 6 +++--- .../include/moveit/collision_detection/collision_matrix.h | 6 +++--- .../moveit/collision_detection/collision_octomap_filter.h | 6 +++--- .../include/moveit/collision_detection/collision_plugin.h | 6 +++--- .../moveit/collision_detection/collision_plugin_cache.h | 6 +++--- .../include/moveit/collision_detection/collision_tools.h | 6 +++--- .../include/moveit/collision_detection/occupancy_map.h | 6 +++--- .../collision_detection/test_collision_common_panda.h | 6 +++--- .../moveit/collision_detection/test_collision_common_pr2.h | 6 +++--- .../include/moveit/collision_detection/world.h | 6 +++--- .../include/moveit/collision_detection/world_diff.h | 6 +++--- .../bullet_integration/basic_types.h | 6 +++--- .../bullet_integration/bullet_bvh_manager.h | 6 +++--- .../bullet_integration/bullet_cast_bvh_manager.h | 6 +++--- .../bullet_integration/bullet_discrete_bvh_manager.h | 6 +++--- .../bullet_integration/bullet_utils.h | 6 +++--- .../bullet_integration/contact_checker_common.h | 6 +++--- .../bullet_integration/ros_bullet_utils.h | 6 +++--- .../collision_detector_allocator_bullet.h | 6 +++--- .../collision_detector_bullet_plugin_loader.h | 6 +++--- .../collision_detection_bullet/collision_env_bullet.h | 6 +++--- .../moveit/collision_detection_fcl/collision_common.h | 6 +++--- .../collision_detector_allocator_fcl.h | 6 +++--- .../collision_detector_fcl_plugin_loader.h | 6 +++--- .../moveit/collision_detection_fcl/collision_env_fcl.h | 6 +++--- .../include/moveit/collision_detection_fcl/fcl_compat.h | 6 +++--- .../collision_common_distance_field.h | 6 +++--- .../collision_detector_allocator_distance_field.h | 6 +++--- .../collision_detector_allocator_hybrid.h | 6 +++--- .../collision_distance_field_types.h | 6 +++--- .../collision_distance_field/collision_env_distance_field.h | 6 +++--- .../moveit/collision_distance_field/collision_env_hybrid.h | 6 +++--- .../include/moveit/constraint_samplers/constraint_sampler.h | 6 +++--- .../constraint_samplers/constraint_sampler_allocator.h | 6 +++--- .../moveit/constraint_samplers/constraint_sampler_manager.h | 6 +++--- .../moveit/constraint_samplers/constraint_sampler_tools.h | 6 +++--- .../constraint_samplers/default_constraint_samplers.h | 6 +++--- .../moveit/constraint_samplers/union_constraint_sampler.h | 6 +++--- .../include/moveit/controller_manager/controller_manager.h | 6 +++--- .../include/moveit/distance_field/distance_field.h | 6 +++--- .../include/moveit/distance_field/find_internal_points.h | 6 +++--- .../moveit/distance_field/propagation_distance_field.h | 6 +++--- .../include/moveit/distance_field/voxel_grid.h | 6 +++--- .../include/moveit/dynamics_solver/dynamics_solver.h | 6 +++--- .../exceptions/include/moveit/exceptions/exceptions.h | 6 +++--- .../moveit/kinematic_constraints/kinematic_constraint.h | 6 +++--- .../include/moveit/kinematic_constraints/utils.h | 6 +++--- .../include/moveit/kinematics_base/kinematics_base.h | 6 +++--- .../include/moveit/kinematics_metrics/kinematics_metrics.h | 6 +++--- moveit_core/macros/include/moveit/macros/class_forward.h | 6 +++--- moveit_core/macros/include/moveit/macros/console_colors.h | 6 +++--- moveit_core/macros/include/moveit/macros/declare_ptr.h | 6 +++--- moveit_core/macros/include/moveit/macros/deprecation.h | 6 +++--- .../moveit/online_signal_smoothing/acceleration_filter.h | 6 +++--- .../moveit/online_signal_smoothing/butterworth_filter.h | 6 +++--- .../include/moveit/online_signal_smoothing/ruckig_filter.h | 6 +++--- .../moveit/online_signal_smoothing/smoothing_base_class.h | 6 +++--- .../include/moveit/planning_interface/planning_interface.h | 6 +++--- .../include/moveit/planning_interface/planning_request.h | 6 +++--- .../moveit/planning_interface/planning_request_adapter.h | 6 +++--- .../include/moveit/planning_interface/planning_response.h | 6 +++--- .../moveit/planning_interface/planning_response_adapter.h | 6 +++--- .../include/moveit/planning_scene/planning_scene.h | 6 +++--- moveit_core/robot_model/include/moveit/robot_model/aabb.h | 6 +++--- .../include/moveit/robot_model/fixed_joint_model.h | 6 +++--- .../include/moveit/robot_model/floating_joint_model.h | 6 +++--- .../robot_model/include/moveit/robot_model/joint_model.h | 6 +++--- .../include/moveit/robot_model/joint_model_group.h | 6 +++--- .../robot_model/include/moveit/robot_model/link_model.h | 6 +++--- .../include/moveit/robot_model/planar_joint_model.h | 6 +++--- .../include/moveit/robot_model/prismatic_joint_model.h | 6 +++--- .../include/moveit/robot_model/revolute_joint_model.h | 6 +++--- .../robot_model/include/moveit/robot_model/robot_model.h | 6 +++--- .../robot_state/include/moveit/robot_state/attached_body.h | 6 +++--- .../include/moveit/robot_state/cartesian_interpolator.h | 6 +++--- .../robot_state/include/moveit/robot_state/conversions.h | 6 +++--- .../robot_state/include/moveit/robot_state/robot_state.h | 6 +++--- .../include/moveit/robot_trajectory/robot_trajectory.h | 6 +++--- .../moveit/trajectory_processing/ruckig_traj_smoothing.h | 6 +++--- .../time_optimal_trajectory_generation.h | 6 +++--- .../moveit/trajectory_processing/time_parameterization.h | 6 +++--- .../include/moveit/trajectory_processing/trajectory_tools.h | 6 +++--- .../transforms/include/moveit/transforms/transforms.h | 6 +++--- moveit_core/utils/include/moveit/utils/eigen_test_utils.h | 6 +++--- moveit_core/utils/include/moveit/utils/lexical_casts.h | 6 +++--- moveit_core/utils/include/moveit/utils/logger.h | 6 +++--- moveit_core/utils/include/moveit/utils/message_checks.h | 6 +++--- moveit_core/utils/include/moveit/utils/moveit_error_code.h | 6 +++--- moveit_core/utils/include/moveit/utils/rclcpp_utils.h | 6 +++--- .../utils/include/moveit/utils/robot_model_test_utils.h | 6 +++--- .../cached_ik_kinematics_plugin-inl.h | 6 +++--- .../cached_ik_kinematics_plugin.h | 6 +++--- .../cached_ik_kinematics_plugin/detail/GreedyKCenters.h | 6 +++--- .../cached_ik_kinematics_plugin/detail/NearestNeighbors.h | 6 +++--- .../detail/NearestNeighborsGNAT.h | 6 +++--- .../kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h | 6 +++--- .../include/moveit/kdl_kinematics_plugin/joint_mimic.h | 6 +++--- .../moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h | 6 +++--- .../moveit/srv_kinematics_plugin/srv_kinematics_plugin.h | 6 +++--- .../include/chomp_interface/chomp_interface.h | 6 +++--- .../include/chomp_interface/chomp_planning_context.h | 6 +++--- .../include/chomp_motion_planner/chomp_cost.h | 6 +++--- .../include/chomp_motion_planner/chomp_optimizer.h | 6 +++--- .../include/chomp_motion_planner/chomp_parameters.h | 6 +++--- .../include/chomp_motion_planner/chomp_planner.h | 6 +++--- .../include/chomp_motion_planner/chomp_trajectory.h | 6 +++--- .../include/chomp_motion_planner/chomp_utils.h | 6 +++--- .../include/chomp_motion_planner/multivariate_gaussian.h | 6 +++--- .../moveit/ompl_interface/detail/constrained_goal_sampler.h | 6 +++--- .../moveit/ompl_interface/detail/constrained_sampler.h | 6 +++--- .../ompl_interface/detail/constraint_approximations.h | 6 +++--- .../moveit/ompl_interface/detail/constraints_library.h | 6 +++--- .../include/moveit/ompl_interface/detail/goal_union.h | 6 +++--- .../include/moveit/ompl_interface/detail/ompl_constraints.h | 6 +++--- .../moveit/ompl_interface/detail/projection_evaluators.h | 6 +++--- .../moveit/ompl_interface/detail/state_validity_checker.h | 6 +++--- .../moveit/ompl_interface/detail/threadsafe_state_storage.h | 6 +++--- .../moveit/ompl_interface/model_based_planning_context.h | 6 +++--- .../include/moveit/ompl_interface/ompl_interface.h | 6 +++--- .../joint_space/constrained_planning_state_space.h | 6 +++--- .../joint_space/constrained_planning_state_space_factory.h | 6 +++--- .../parameterization/joint_space/joint_model_state_space.h | 6 +++--- .../joint_space/joint_model_state_space_factory.h | 6 +++--- .../parameterization/model_based_state_space.h | 6 +++--- .../parameterization/model_based_state_space_factory.h | 6 +++--- .../parameterization/work_space/pose_model_state_space.h | 6 +++--- .../work_space/pose_model_state_space_factory.h | 6 +++--- .../moveit/ompl_interface/planning_context_manager.h | 6 +++--- .../include/joint_limits_copy/joint_limits.h | 6 +++--- .../include/joint_limits_copy/joint_limits_rosparam.h | 6 +++--- .../pilz_industrial_motion_planner/capability_names.h | 6 +++--- .../pilz_industrial_motion_planner/cartesian_trajectory.h | 6 +++--- .../cartesian_trajectory_point.h | 6 +++--- .../pilz_industrial_motion_planner/command_list_manager.h | 6 +++--- .../joint_limits_aggregator.h | 6 +++--- .../pilz_industrial_motion_planner/joint_limits_container.h | 6 +++--- .../pilz_industrial_motion_planner/joint_limits_extension.h | 6 +++--- .../joint_limits_interface_extension.h | 6 +++--- .../pilz_industrial_motion_planner/joint_limits_validator.h | 6 +++--- .../pilz_industrial_motion_planner/limits_container.h | 6 +++--- .../move_group_sequence_action.h | 6 +++--- .../move_group_sequence_service.h | 6 +++--- .../pilz_industrial_motion_planner/path_circle_generator.h | 6 +++--- .../pilz_industrial_motion_planner.h | 6 +++--- .../plan_components_builder.h | 6 +++--- .../pilz_industrial_motion_planner/planning_context_base.h | 6 +++--- .../pilz_industrial_motion_planner/planning_context_circ.h | 6 +++--- .../pilz_industrial_motion_planner/planning_context_lin.h | 6 +++--- .../planning_context_loader.h | 6 +++--- .../planning_context_loader_circ.h | 6 +++--- .../planning_context_loader_lin.h | 6 +++--- .../planning_context_loader_ptp.h | 6 +++--- .../pilz_industrial_motion_planner/planning_context_ptp.h | 6 +++--- .../pilz_industrial_motion_planner/planning_exceptions.h | 6 +++--- .../pilz_industrial_motion_planner/tip_frame_getter.h | 6 +++--- .../trajectory_blend_request.h | 6 +++--- .../trajectory_blend_response.h | 6 +++--- .../pilz_industrial_motion_planner/trajectory_blender.h | 6 +++--- .../trajectory_blender_transition_window.h | 6 +++--- .../pilz_industrial_motion_planner/trajectory_functions.h | 6 +++--- .../trajectory_generation_exceptions.h | 6 +++--- .../pilz_industrial_motion_planner/trajectory_generator.h | 6 +++--- .../trajectory_generator_circ.h | 6 +++--- .../trajectory_generator_lin.h | 6 +++--- .../trajectory_generator_ptp.h | 6 +++--- .../pilz_industrial_motion_planner/velocity_profile_atrap.h | 6 +++--- .../pilz_industrial_motion_planner_testutils/async_test.h | 6 +++--- .../pilz_industrial_motion_planner_testutils/basecmd.h | 6 +++--- .../cartesianconfiguration.h | 6 +++--- .../cartesianpathconstraintsbuilder.h | 6 +++--- .../pilz_industrial_motion_planner_testutils/center.h | 6 +++--- .../pilz_industrial_motion_planner_testutils/checks.h | 6 +++--- .../include/pilz_industrial_motion_planner_testutils/circ.h | 6 +++--- .../circ_auxiliary_types.h | 6 +++--- .../circauxiliary.h | 6 +++--- .../command_types_typedef.h | 6 +++--- .../default_values.h | 6 +++--- .../exception_types.h | 6 +++--- .../goalconstraintsmsgconvertible.h | 6 +++--- .../pilz_industrial_motion_planner_testutils/gripper.h | 6 +++--- .../pilz_industrial_motion_planner_testutils/interim.h | 6 +++--- .../jointconfiguration.h | 6 +++--- .../include/pilz_industrial_motion_planner_testutils/lin.h | 6 +++--- .../pilz_industrial_motion_planner_testutils/motioncmd.h | 6 +++--- .../motionplanrequestconvertible.h | 6 +++--- .../include/pilz_industrial_motion_planner_testutils/ptp.h | 6 +++--- .../robotconfiguration.h | 6 +++--- .../robotstatemsgconvertible.h | 6 +++--- .../pilz_industrial_motion_planner_testutils/sequence.h | 6 +++--- .../testdata_loader.h | 6 +++--- .../xml_constants.h | 6 +++--- .../xml_testdata_loader.h | 6 +++--- .../stomp/include/stomp_moveit/conversion_functions.h | 6 +++--- moveit_planners/stomp/include/stomp_moveit/cost_functions.h | 6 +++--- .../stomp/include/stomp_moveit/filter_functions.h | 6 +++--- .../stomp/include/stomp_moveit/math/multivariate_gaussian.h | 6 +++--- .../stomp/include/stomp_moveit/noise_generators.h | 6 +++--- .../include/stomp_moveit/stomp_moveit_planning_context.h | 6 +++--- .../stomp/include/stomp_moveit/stomp_moveit_task.h | 6 +++--- .../stomp/include/stomp_moveit/trajectory_visualization.h | 6 +++--- .../include/moveit_ros_control_interface/ControllerHandle.h | 6 +++--- .../action_based_controller_handle.h | 6 +++--- .../empty_controller_handle.h | 6 +++--- .../follow_joint_trajectory_controller_handle.h | 6 +++--- .../gripper_controller_handle.h | 6 +++--- .../include/moveit_py/moveit_py_utils/copy_ros_msg.h | 6 +++--- .../include/moveit_py/moveit_py_utils/ros_msg_typecasters.h | 6 +++--- .../include/moveit/benchmarks/BenchmarkExecutor.h | 6 +++--- .../benchmarks/include/moveit/benchmarks/BenchmarkOptions.h | 6 +++--- .../moveit/global_planner/global_planner_component.h | 6 +++--- .../moveit/global_planner/global_planner_interface.h | 6 +++--- .../moveit/global_planner/moveit_planning_pipeline.h | 6 +++--- .../moveit/hybrid_planning_manager/hybrid_planning_events.h | 6 +++--- .../hybrid_planning_manager/hybrid_planning_manager.h | 6 +++--- .../hybrid_planning_manager/planner_logic_interface.h | 6 +++--- .../planner_logic_plugins/replan_invalidated_trajectory.h | 6 +++--- .../moveit/planner_logic_plugins/single_plan_execution.h | 6 +++--- .../local_constraint_solver_plugins/forward_trajectory.h | 6 +++--- .../include/moveit/local_planner/feedback_types.h | 6 +++--- .../local_planner/local_constraint_solver_interface.h | 6 +++--- .../include/moveit/local_planner/local_planner_component.h | 6 +++--- .../moveit/local_planner/trajectory_operator_interface.h | 6 +++--- .../moveit/trajectory_operator_plugins/simple_sampler.h | 6 +++--- .../move_group/include/moveit/move_group/capability_names.h | 6 +++--- .../include/moveit/move_group/move_group_capability.h | 6 +++--- .../include/moveit/move_group/move_group_context.h | 6 +++--- .../moveit_servo/include/moveit_servo/collision_monitor.h | 6 +++--- moveit_ros/moveit_servo/include/moveit_servo/servo.h | 6 +++--- moveit_ros/moveit_servo/include/moveit_servo/servo_node.h | 6 +++--- .../moveit_servo/include/moveit_servo/utils/command.h | 6 +++--- moveit_ros/moveit_servo/include/moveit_servo/utils/common.h | 6 +++--- .../moveit_servo/include/moveit_servo/utils/datatypes.h | 6 +++--- .../moveit/occupancy_map_monitor/occupancy_map_monitor.h | 6 +++--- .../occupancy_map_monitor_middleware_handle.h | 6 +++--- .../moveit/occupancy_map_monitor/occupancy_map_updater.h | 6 +++--- .../depth_image_octomap_updater.h | 6 +++--- .../lazy_free_space_updater/lazy_free_space_updater.h | 6 +++--- .../include/moveit/mesh_filter/depth_self_filter_nodelet.h | 6 +++--- .../mesh_filter/include/moveit/mesh_filter/filter_job.h | 6 +++--- .../mesh_filter/include/moveit/mesh_filter/gl_mesh.h | 6 +++--- .../mesh_filter/include/moveit/mesh_filter/gl_renderer.h | 6 +++--- .../mesh_filter/include/moveit/mesh_filter/mesh_filter.h | 6 +++--- .../include/moveit/mesh_filter/mesh_filter_base.h | 6 +++--- .../mesh_filter/include/moveit/mesh_filter/sensor_model.h | 6 +++--- .../include/moveit/mesh_filter/stereo_camera_model.h | 6 +++--- .../include/moveit/mesh_filter/transform_provider.h | 6 +++--- .../include/moveit/point_containment_filter/shape_mask.h | 6 +++--- .../pointcloud_octomap_updater/pointcloud_octomap_updater.h | 6 +++--- .../include/moveit/semantic_world/semantic_world.h | 6 +++--- .../collision_plugin_loader/collision_plugin_loader.h | 6 +++--- .../constraint_sampler_manager_loader.h | 6 +++--- .../kinematics_plugin_loader/kinematics_plugin_loader.h | 6 +++--- .../moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h | 6 +++--- .../include/moveit/moveit_cpp/planning_component.h | 6 +++--- .../include/moveit/plan_execution/plan_execution.h | 6 +++--- .../include/moveit/plan_execution/plan_representation.h | 6 +++--- .../include/moveit/planning_pipeline/planning_pipeline.h | 6 +++--- .../planning_pipeline_interfaces/plan_responses_container.h | 6 +++--- .../planning_pipeline_interfaces.h | 6 +++--- .../solution_selection_functions.h | 6 +++--- .../stopping_criterion_functions.h | 6 +++--- .../moveit/planning_scene_monitor/current_state_monitor.h | 6 +++--- .../current_state_monitor_middleware_handle.h | 6 +++--- .../moveit/planning_scene_monitor/planning_scene_monitor.h | 6 +++--- .../moveit/planning_scene_monitor/trajectory_monitor.h | 6 +++--- .../trajectory_monitor_middleware_handle.h | 6 +++--- .../rdf_loader/include/moveit/rdf_loader/rdf_loader.h | 6 +++--- .../moveit/rdf_loader/synchronized_string_parameter.h | 6 +++--- .../include/moveit/robot_model_loader/robot_model_loader.h | 6 +++--- .../trajectory_execution_manager.h | 6 +++--- .../common_planning_interface_objects/common_objects.h | 6 +++--- .../moveit/move_group_interface/move_group_interface.h | 6 +++--- .../planning_scene_interface/planning_scene_interface.h | 6 +++--- .../include/moveit/robot_interaction/interaction.h | 6 +++--- .../include/moveit/robot_interaction/interaction_handler.h | 6 +++--- .../moveit/robot_interaction/interactive_marker_helpers.h | 6 +++--- .../include/moveit/robot_interaction/kinematic_options.h | 6 +++--- .../moveit/robot_interaction/kinematic_options_map.h | 6 +++--- .../include/moveit/robot_interaction/locked_robot_state.h | 6 +++--- .../include/moveit/robot_interaction/robot_interaction.h | 6 +++--- moveit_ros/tests/include/parameter_name_list.h | 6 +++--- .../include/moveit/trajectory_cache/trajectory_cache.h | 6 +++--- .../interactive_marker_display.h | 6 +++--- .../motion_planning_rviz_plugin/motion_planning_display.h | 6 +++--- .../motion_planning_rviz_plugin/motion_planning_frame.h | 6 +++--- .../motion_planning_frame_joints_widget.h | 6 +++--- .../motion_planning_param_widget.h | 6 +++--- .../planning_scene_rviz_plugin/background_processing.h | 6 +++--- .../planning_scene_rviz_plugin/planning_scene_display.h | 6 +++--- .../moveit/robot_state_rviz_plugin/robot_state_display.h | 6 +++--- .../moveit/rviz_plugin_render_tools/octomap_render.h | 6 +++--- .../moveit/rviz_plugin_render_tools/planning_link_updater.h | 6 +++--- .../moveit/rviz_plugin_render_tools/planning_scene_render.h | 6 +++--- .../include/moveit/rviz_plugin_render_tools/render_shapes.h | 6 +++--- .../rviz_plugin_render_tools/robot_state_visualization.h | 6 +++--- .../moveit/rviz_plugin_render_tools/trajectory_panel.h | 6 +++--- .../rviz_plugin_render_tools/trajectory_visualization.h | 6 +++--- .../include/ogre_helpers/mesh_shape.h | 6 +++--- .../moveit/trajectory_rviz_plugin/trajectory_display.h | 6 +++--- .../include/moveit/warehouse/constraints_storage.h | 6 +++--- .../include/moveit/warehouse/moveit_message_storage.h | 6 +++--- .../include/moveit/warehouse/planning_scene_storage.h | 6 +++--- .../include/moveit/warehouse/planning_scene_world_storage.h | 6 +++--- .../warehouse/include/moveit/warehouse/state_storage.h | 6 +++--- .../moveit/warehouse/trajectory_constraints_storage.h | 6 +++--- .../include/moveit/warehouse/warehouse_connector.h | 6 +++--- .../include/moveit_setup_app_plugins/launch_bundle.h | 6 +++--- .../include/moveit_setup_app_plugins/launches.h | 6 +++--- .../include/moveit_setup_app_plugins/launches_config.h | 6 +++--- .../include/moveit_setup_app_plugins/launches_widget.h | 6 +++--- .../include/moveit_setup_app_plugins/perception.h | 6 +++--- .../include/moveit_setup_app_plugins/perception_config.h | 6 +++--- .../include/moveit_setup_app_plugins/perception_widget.h | 6 +++--- .../include/moveit_setup_assistant/navigation_widget.h | 6 +++--- .../include/moveit_setup_assistant/setup_assistant_widget.h | 6 +++--- .../include/moveit_setup_controllers/control_xacro_config.h | 6 +++--- .../moveit_setup_controllers/controller_edit_widget.h | 6 +++--- .../include/moveit_setup_controllers/controllers.h | 6 +++--- .../include/moveit_setup_controllers/controllers_config.h | 6 +++--- .../include/moveit_setup_controllers/controllers_widget.h | 6 +++--- .../moveit_setup_controllers/included_xacro_config.h | 6 +++--- .../include/moveit_setup_controllers/modified_urdf_config.h | 6 +++--- .../include/moveit_setup_controllers/moveit_controllers.h | 6 +++--- .../moveit_setup_controllers/moveit_controllers_config.h | 6 +++--- .../include/moveit_setup_controllers/ros2_controllers.h | 6 +++--- .../moveit_setup_controllers/ros2_controllers_config.h | 6 +++--- .../include/moveit_setup_controllers/urdf_modifications.h | 6 +++--- .../moveit_setup_controllers/urdf_modifications_widget.h | 6 +++--- .../include/moveit_setup_core_plugins/author_information.h | 6 +++--- .../moveit_setup_core_plugins/author_information_widget.h | 6 +++--- .../include/moveit_setup_core_plugins/configuration_files.h | 6 +++--- .../moveit_setup_core_plugins/configuration_files_widget.h | 6 +++--- .../include/moveit_setup_core_plugins/start_screen.h | 6 +++--- .../include/moveit_setup_core_plugins/start_screen_widget.h | 6 +++--- .../include/moveit_setup_framework/config.h | 6 +++--- .../moveit_setup_framework/data/package_settings_config.h | 6 +++--- .../include/moveit_setup_framework/data/srdf_config.h | 6 +++--- .../include/moveit_setup_framework/data/urdf_config.h | 6 +++--- .../include/moveit_setup_framework/data_warehouse.h | 6 +++--- .../include/moveit_setup_framework/generated_file.h | 6 +++--- .../include/moveit_setup_framework/generated_time.h | 6 +++--- .../include/moveit_setup_framework/qt/double_list_widget.h | 6 +++--- .../include/moveit_setup_framework/qt/helper_widgets.h | 6 +++--- .../include/moveit_setup_framework/qt/rviz_panel.h | 6 +++--- .../include/moveit_setup_framework/qt/setup_step_widget.h | 6 +++--- .../moveit_setup_framework/qt/xml_syntax_highlighter.h | 6 +++--- .../include/moveit_setup_framework/setup_step.h | 6 +++--- .../include/moveit_setup_framework/templates.h | 6 +++--- .../include/moveit_setup_framework/testing_utils.h | 6 +++--- .../include/moveit_setup_framework/utilities.h | 6 +++--- .../include/moveit_setup_simulation/simulation.h | 6 +++--- .../include/moveit_setup_simulation/simulation_widget.h | 6 +++--- .../moveit_setup_srdf_plugins/collision_linear_model.h | 6 +++--- .../moveit_setup_srdf_plugins/collision_matrix_model.h | 6 +++--- .../moveit_setup_srdf_plugins/compute_default_collisions.h | 6 +++--- .../include/moveit_setup_srdf_plugins/default_collisions.h | 6 +++--- .../moveit_setup_srdf_plugins/default_collisions_widget.h | 6 +++--- .../include/moveit_setup_srdf_plugins/end_effectors.h | 6 +++--- .../moveit_setup_srdf_plugins/end_effectors_widget.h | 6 +++--- .../include/moveit_setup_srdf_plugins/group_edit_widget.h | 6 +++--- .../include/moveit_setup_srdf_plugins/group_meta_config.h | 6 +++--- .../moveit_setup_srdf_plugins/kinematic_chain_widget.h | 6 +++--- .../include/moveit_setup_srdf_plugins/passive_joints.h | 6 +++--- .../moveit_setup_srdf_plugins/passive_joints_widget.h | 6 +++--- .../include/moveit_setup_srdf_plugins/planning_groups.h | 6 +++--- .../moveit_setup_srdf_plugins/planning_groups_widget.h | 6 +++--- .../include/moveit_setup_srdf_plugins/robot_poses.h | 6 +++--- .../include/moveit_setup_srdf_plugins/robot_poses_widget.h | 6 +++--- .../include/moveit_setup_srdf_plugins/rotated_header_view.h | 6 +++--- .../include/moveit_setup_srdf_plugins/srdf_step.h | 6 +++--- .../include/moveit_setup_srdf_plugins/virtual_joints.h | 6 +++--- .../moveit_setup_srdf_plugins/virtual_joints_widget.h | 6 +++--- 376 files changed, 1128 insertions(+), 1128 deletions(-) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h index e4612075c4..46a87f0e7f 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h index 5e170761d9..8057b05872 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h index ec90518579..99a2a3e43b 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h index a4603a6684..4af6061a5c 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h index a0a8620fae..bf1c537381 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h index 7398244de1..6b3eec200d 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h index cce836826d..a681964d85 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h index 2008f2d6f1..ed27b3349b 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h index 16a7cbae83..ee023950a2 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h index 355b7f21d1..ec0c4ad0e5 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h b/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h index 287e5378ab..77079b51b9 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h index 196b0a5319..a84fb9d799 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h index c5cc2355eb..55bcf1a7e1 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/world.h b/moveit_core/collision_detection/include/moveit/collision_detection/world.h index 6ae557dc63..d4428b00bb 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/world.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/world.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h b/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h index e3b36bc100..dff078f69a 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h index f35acaa28e..3210a0d419 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (Apache License) @@ -22,6 +22,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h index cfda30bef9..8ea976e4b8 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD-2-Clause) @@ -35,6 +35,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h index 8956a9540a..1604585f5c 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD-2-Clause) @@ -35,6 +35,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h index 86ce5f70a2..95288fec1d 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD-2-Clause) @@ -35,6 +35,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h index 1b598cd41c..9e1d841602 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD-2-Clause) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h index 3b37237188..9f96fb1404 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (Apache License) @@ -22,6 +22,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h index 714bf2c5c1..05e155d59f 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (Apache License) @@ -22,6 +22,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h index 5b94987544..e18cdb7650 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h index 9c4fbfa748..d0c46b607b 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h index ea969018d3..03fe11fac5 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h index 30f45c8648..61243ca3f5 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h index 5587a69563..c0349364dc 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h index 87f2e8df55..de1966c28b 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h index 97efefe834..04146056a3 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h index 82b8b9dcac..f353a6ae24 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h index 76d3390115..0f601d4fcf 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h index f0d43d75cc..adf9fd35d3 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h index 47dcc1c38f..bb3aafbd3a 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h index 4374597bff..87f7574861 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h index 79ccf9a654..a077c1be79 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h index 9635a377e1..1dbe760be3 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h index ec74f6b91a..ac88859f01 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h index d80a16739f..662f649868 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h index e41302158b..99a669dcf3 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h index e030f26a22..d5f8ffd2a4 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h index dbf893f407..76f739d855 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h index 02337e72c9..1ab75af0b7 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h b/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h index 905d928455..f1ae07e744 100644 --- a/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h +++ b/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/distance_field/include/moveit/distance_field/distance_field.h b/moveit_core/distance_field/include/moveit/distance_field/distance_field.h index 7b54b5eba0..9ed8e2a4b4 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/distance_field.h +++ b/moveit_core/distance_field/include/moveit/distance_field/distance_field.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h b/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h index 9942543c46..1d4fe0ffd8 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h +++ b/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h b/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h index 1413557278..901891c127 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h +++ b/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h b/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h index 2a0435fe16..25a4185324 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h +++ b/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h b/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h index e0ddc6ee20..3af00567ad 100644 --- a/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h +++ b/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/exceptions/include/moveit/exceptions/exceptions.h b/moveit_core/exceptions/include/moveit/exceptions/exceptions.h index 8647d73f11..58b97119eb 100644 --- a/moveit_core/exceptions/include/moveit/exceptions/exceptions.h +++ b/moveit_core/exceptions/include/moveit/exceptions/exceptions.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h index 73cf72897b..e4458b541b 100644 --- a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h +++ b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h index 700e685583..e4937b10bf 100644 --- a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h +++ b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h index 2f6850255c..2a7966c4b7 100644 --- a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h +++ b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h b/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h index ea5bbd2005..29392d6013 100644 --- a/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h +++ b/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/macros/include/moveit/macros/class_forward.h b/moveit_core/macros/include/moveit/macros/class_forward.h index 78901b394b..615708cc9e 100644 --- a/moveit_core/macros/include/moveit/macros/class_forward.h +++ b/moveit_core/macros/include/moveit/macros/class_forward.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/macros/include/moveit/macros/console_colors.h b/moveit_core/macros/include/moveit/macros/console_colors.h index 713c954720..9098a338f6 100644 --- a/moveit_core/macros/include/moveit/macros/console_colors.h +++ b/moveit_core/macros/include/moveit/macros/console_colors.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/macros/include/moveit/macros/declare_ptr.h b/moveit_core/macros/include/moveit/macros/declare_ptr.h index f80d6d0057..586a142d33 100644 --- a/moveit_core/macros/include/moveit/macros/declare_ptr.h +++ b/moveit_core/macros/include/moveit/macros/declare_ptr.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/macros/include/moveit/macros/deprecation.h b/moveit_core/macros/include/moveit/macros/deprecation.h index 53e9533ac5..b0b6670cdd 100644 --- a/moveit_core/macros/include/moveit/macros/deprecation.h +++ b/moveit_core/macros/include/moveit/macros/deprecation.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h index eb118c706d..a3010df82d 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -74,6 +74,6 @@ c --------x--- v | #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h index 07dcb3ae3d..fef50eb661 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -41,6 +41,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h index 3ad48b6daf..3ebd65db48 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -40,6 +40,6 @@ Description: Applies jerk/acceleration/velocity limits to online motion commands #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h index 46e83a6937..e165d715f5 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -40,6 +40,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h index 2c213c3a19..d57a887b2e 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h index 1fcfe02957..385f27b52c 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h index bca74f5256..3613557f18 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -40,6 +40,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h index 53770b38a5..877b1c1bfb 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h index 4d8ab1c948..a7dd1ebd4b 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h index 93cc4ffebe..acd09c66ed 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/robot_model/include/moveit/robot_model/aabb.h b/moveit_core/robot_model/include/moveit/robot_model/aabb.h index c959fe3f64..20ed6d0e80 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/aabb.h +++ b/moveit_core/robot_model/include/moveit/robot_model/aabb.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h index e672ed4bf6..f9788be573 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h index f9e63b0923..1f25091581 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/robot_model/include/moveit/robot_model/joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/joint_model.h index fa2c4ccdb9..c70ec2e7eb 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/joint_model.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -39,6 +39,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h index 678a416462..1c572d8efd 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h +++ b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -39,6 +39,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/robot_model/include/moveit/robot_model/link_model.h b/moveit_core/robot_model/include/moveit/robot_model/link_model.h index 481ce4b8c5..b1b8d564ac 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/link_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/link_model.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h index f53cefcfc4..309ba8d001 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h index f86748305c..792ff303fb 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h index 2c90b6f926..1071b25a3e 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h index 97adcf6b5e..947087c152 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -39,6 +39,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/robot_state/include/moveit/robot_state/attached_body.h b/moveit_core/robot_state/include/moveit/robot_state/attached_body.h index 26fae9b016..30ea3b015a 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/attached_body.h +++ b/moveit_core/robot_state/include/moveit/robot_state/attached_body.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h b/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h index 8cd6a999d9..361f9e1882 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h +++ b/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -40,6 +40,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/robot_state/include/moveit/robot_state/conversions.h b/moveit_core/robot_state/include/moveit/robot_state/conversions.h index 676667dba5..c6b6e0b0f0 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/conversions.h +++ b/moveit_core/robot_state/include/moveit/robot_state/conversions.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h index 398b96a46e..c6b1e98a0b 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h +++ b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -39,6 +39,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h index 7adef007c3..d8b6a64c5d 100644 --- a/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h +++ b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h index 19b3b0c436..a4bb2cf573 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /******************************************************************************* * BSD 3-Clause License @@ -37,6 +37,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h index 874d7256cc..7adb051d78 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /* * Copyright (c) 2011-2012, Georgia Tech Research Corporation @@ -40,6 +40,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h index ce63309901..9f5fb81801 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h @@ -1,7 +1,7 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h index 3da16de211..344e24f289 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/transforms/include/moveit/transforms/transforms.h b/moveit_core/transforms/include/moveit/transforms/transforms.h index 400672a775..63a657e0fd 100644 --- a/moveit_core/transforms/include/moveit/transforms/transforms.h +++ b/moveit_core/transforms/include/moveit/transforms/transforms.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/utils/include/moveit/utils/eigen_test_utils.h b/moveit_core/utils/include/moveit/utils/eigen_test_utils.h index 6edc813391..5bc646070d 100644 --- a/moveit_core/utils/include/moveit/utils/eigen_test_utils.h +++ b/moveit_core/utils/include/moveit/utils/eigen_test_utils.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/utils/include/moveit/utils/lexical_casts.h b/moveit_core/utils/include/moveit/utils/lexical_casts.h index 25e2c9ae3e..4b3763a561 100644 --- a/moveit_core/utils/include/moveit/utils/lexical_casts.h +++ b/moveit_core/utils/include/moveit/utils/lexical_casts.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/utils/include/moveit/utils/logger.h b/moveit_core/utils/include/moveit/utils/logger.h index 0cc31ac22a..8407c8d060 100644 --- a/moveit_core/utils/include/moveit/utils/logger.h +++ b/moveit_core/utils/include/moveit/utils/logger.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/utils/include/moveit/utils/message_checks.h b/moveit_core/utils/include/moveit/utils/message_checks.h index 2f80182981..ffdee74e59 100644 --- a/moveit_core/utils/include/moveit/utils/message_checks.h +++ b/moveit_core/utils/include/moveit/utils/message_checks.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/utils/include/moveit/utils/moveit_error_code.h b/moveit_core/utils/include/moveit/utils/moveit_error_code.h index 293751a2b4..93eb88b1bb 100644 --- a/moveit_core/utils/include/moveit/utils/moveit_error_code.h +++ b/moveit_core/utils/include/moveit/utils/moveit_error_code.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/utils/include/moveit/utils/rclcpp_utils.h b/moveit_core/utils/include/moveit/utils/rclcpp_utils.h index 84bb3ad038..91bdb167a0 100644 --- a/moveit_core/utils/include/moveit/utils/rclcpp_utils.h +++ b/moveit_core/utils/include/moveit/utils/rclcpp_utils.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /* * Copyright (C) 2009, Willow Garage, Inc. @@ -29,6 +29,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h b/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h index 7487bc783b..87eb4622bb 100644 --- a/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h +++ b/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -39,6 +39,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h index 060faaee2c..fa310d550c 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h index ff7d0df1a1..3587f2ed3f 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h index 1633372a05..031f15d265 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -40,6 +40,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h index 34c074bf61..d0c5be3032 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -40,6 +40,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h index 3978ba0e31..efb6068acf 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -40,6 +40,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h index 097acec5ad..4e0cad00c7 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h +++ b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ // Copyright (C) 2007 Ruben Smits @@ -27,6 +27,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h index eedf098569..0808dc431b 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h +++ b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h index 87f914d4e1..367f77b5ce 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h +++ b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h b/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h index 18816e3829..c8f0df3a5a 100644 --- a/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h +++ b/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -43,6 +43,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h index 858adc9f14..baa38800f8 100644 --- a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h +++ b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h index eac76c8665..2d6884e485 100644 --- a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h +++ b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h index ef40b9e774..0bab0ca82d 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h index ebf7e4c16a..cccdf40aec 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h index 12d84dfee0..6baab5f32e 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -41,6 +41,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h index 2552ff7f1f..be79d1b6f9 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h index 8e453e54c1..70d54639c4 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h index 8bb66984c4..6bd816a0a9 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h index 5bb1e6a327..554bd1f31b 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h index 8fec013598..71e03612e6 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h index cf7db621e4..e62686e8dc 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h index d76b102f17..0aa71101fa 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h index 4104cf0725..dc47c60535 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h index de8b8f9c16..9f0c221973 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h index 58e60dda2c..9a11b88e57 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h index d76fdacde8..1f401618a7 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h index 65cb13ec64..a7be4cc1f0 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -49,6 +49,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h index 24b973f15e..1f1c3373e8 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h index 4e6bdbbf3b..a99c2cb84b 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h index 6aa8f78b29..f3fc050205 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h index 46403ae15d..04acc05227 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h index 89632d608c..233f11f42e 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -39,6 +39,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h index a01838fcef..ee2426f442 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h index 215e60cedb..267a3bbc31 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h index e0848378a3..9ad24a8e20 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h index 4538ac92d1..37a74cd90e 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h index b5e6e3efae..b38741bd6a 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h index 5674788016..9d56e5136f 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h index da8b5383e3..5ffa3ca325 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h index 5dbce8ff1b..a5b37be196 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ // Copyright 2020 PAL Robotics S.L. // @@ -18,6 +18,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h index 706c468416..e6f335a70d 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ // Copyright 2020 PAL Robotics S.L. // @@ -18,6 +18,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h index a04d3ee9b8..0ca1157de7 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h index a0b47a352f..324a0931e2 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h index bfa545456d..ca7664a0ea 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h index 2f72ccea1d..d0f14a23f4 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h index 45f206765a..d4932cd523 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h index fe677543c5..cdd6eaf316 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h index b7c721bf21..a9f5c554c5 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h index 725ed99a03..a860842eab 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h index 0f92f6c763..cefd648053 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h index 693fe066c7..c902fd4f9d 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h index 9455bf4e0c..508d435714 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h index 4e0f49d996..76c02d2e4a 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h index d154ecfdc7..b8d16394cf 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h index 57c423e66d..bd6de3e652 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h index e8019d19fc..a8cbf2b4ea 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h index 7d3b10d693..27618d49bb 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h index 8165f591e7..dbe4d6a1c9 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h index 1264a93057..e551197760 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h index c45a824c75..01527922f2 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h index cf82c81423..12842205e5 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h index 8f2d763fa9..1f8293a003 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h index 6f75c2cb47..7c963ca0c7 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h index 17f50bccde..84cd985367 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h index 54ab569352..4d6d3d2511 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h index caeadfce7a..868b04e540 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h index ff8a65f497..3ffac85bc7 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h index cef5473190..9dec1b249a 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h index 2617c0872a..892bc4ce00 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h index cb6b210544..a8c09c0ea1 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h index ef4d462c3f..8cbdf117f3 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h index 876f25b2f6..0404071c27 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h index 7e6e9b6986..5abcd0c63c 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h index 737e2d0f85..69605940dd 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h index f316df3e42..05c34019b7 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h index 515ec9d763..b157842300 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h index 8d80cb50df..d315ec8904 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h index 61ff4fb861..98306c8bc3 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /* * Copyright (c) 2018 Pilz GmbH & Co. KG @@ -18,6 +18,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h index d3ca68b498..8988d2ea9a 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h index be4726a356..4ffdf6e663 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h index d49fbb5d3a..2adda44dc9 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h index 152ad9a40d..f445bc2c76 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h index f3a4b4f1c6..07ed9cab4f 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h index 8c5eb215da..dffcead493 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h index 1c963ea1a6..4cb20c1af6 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h index a2366ead6c..ffa7831cd5 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h index 3ab110c526..5ef7daa238 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h index 9d5db58189..34728d78b1 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h index c7c3243824..e0935a4515 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h index 4e272ce40f..193fa060f8 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h index 42b287c9b1..96e1267f58 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h index 2d25069723..b70c46a3e1 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h index 6609b47e87..7ff3b797eb 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h index 59aac2deb0..3fc8bdeffc 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h index b6846e20ca..5e68328b51 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h index 808759cfba..75df8d156e 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h index 5806d8e535..3e85b02371 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h index eab5c7d390..a9538c04c8 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h index 0cec32f96a..d6b96e7e62 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h index cd6c86f0e9..8ab1962490 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h index 6b9d3645e4..95eac3f7a4 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h index cb3b2a5a7f..7cc6f879cf 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h index ff9799c6ee..90f190f887 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h b/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h index 6d35d0ce39..a3af845723 100644 --- a/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h +++ b/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -41,6 +41,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/stomp/include/stomp_moveit/cost_functions.h b/moveit_planners/stomp/include/stomp_moveit/cost_functions.h index d9514ca858..7c7418c929 100644 --- a/moveit_planners/stomp/include/stomp_moveit/cost_functions.h +++ b/moveit_planners/stomp/include/stomp_moveit/cost_functions.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -41,6 +41,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/stomp/include/stomp_moveit/filter_functions.h b/moveit_planners/stomp/include/stomp_moveit/filter_functions.h index 304bac63d3..b6ef586b3f 100644 --- a/moveit_planners/stomp/include/stomp_moveit/filter_functions.h +++ b/moveit_planners/stomp/include/stomp_moveit/filter_functions.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -41,6 +41,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h b/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h index 7d3c63a4d7..92d0659e7b 100644 --- a/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h +++ b/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -41,6 +41,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/stomp/include/stomp_moveit/noise_generators.h b/moveit_planners/stomp/include/stomp_moveit/noise_generators.h index ffa1a8e0f4..80b341b660 100644 --- a/moveit_planners/stomp/include/stomp_moveit/noise_generators.h +++ b/moveit_planners/stomp/include/stomp_moveit/noise_generators.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -41,6 +41,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h index d1a43ad9b5..5bb31068fa 100644 --- a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h +++ b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -41,6 +41,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h index 3d84986024..822b645faa 100644 --- a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h +++ b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -56,6 +56,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h b/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h index e072e61c2d..aef2acf719 100644 --- a/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h +++ b/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -41,6 +41,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h b/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h index bb7ba51126..309076cfe4 100644 --- a/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h +++ b/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h index 4ed45aac84..69b4e45ec7 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -39,6 +39,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h index b7baf0df16..bd08d3f4ba 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h index 9b5037d822..59bcce52a2 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -39,6 +39,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h index 6152239752..a64afec097 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -39,6 +39,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h index 8c9baa1fe6..ebf4587a4f 100644 --- a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h +++ b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h index 20a3bcd65d..ee94381a75 100644 --- a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h +++ b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h index 6d7f157c81..60445cd82c 100644 --- a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h +++ b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h index a0235870b2..8a6b08b4a1 100644 --- a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h +++ b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h index 75cf064de7..6b10c6f8e7 100644 --- a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h +++ b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -40,6 +40,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h index fc98b4b056..2b35e0e598 100644 --- a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h +++ b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -41,6 +41,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h b/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h index ec6b42c5d0..57d8b775a6 100644 --- a/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h +++ b/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -39,6 +39,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h index 7cc4256faf..0d01adf237 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -39,6 +39,6 @@ */ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h index 0c64d5bf4c..bec1a489cd 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -40,6 +40,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h index d52dfc06ee..3b780bf65d 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -40,6 +40,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h index 56598bce51..00a1d61858 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -42,6 +42,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h index f81586a098..119b5e4922 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -41,6 +41,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h b/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h index c5ffee6a8f..9450b37538 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h +++ b/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -42,6 +42,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h index 912dea86ff..63cb254fa4 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -41,6 +41,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h index f9cf7bd1b6..bd5aa4f9ac 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -40,6 +40,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h index a9f4bc8a69..4a76087904 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -41,6 +41,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h index db19c89a08..502de4c984 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -40,6 +40,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h b/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h index f99263c98a..b00d9f7118 100644 --- a/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h +++ b/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -42,6 +42,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/move_group/include/moveit/move_group/capability_names.h b/moveit_ros/move_group/include/moveit/move_group/capability_names.h index 1a4b5dd9d1..d0ed41a3b7 100644 --- a/moveit_ros/move_group/include/moveit/move_group/capability_names.h +++ b/moveit_ros/move_group/include/moveit/move_group/capability_names.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h b/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h index 3cb8f6f981..93b08bda72 100644 --- a/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h +++ b/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/move_group/include/moveit/move_group/move_group_context.h b/moveit_ros/move_group/include/moveit/move_group/move_group_context.h index ae51f9449e..28377b4854 100644 --- a/moveit_ros/move_group/include/moveit/move_group/move_group_context.h +++ b/moveit_ros/move_group/include/moveit/move_group/move_group_context.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h b/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h index cf0f345a3e..8b7887c43e 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /******************************************************************************* * BSD 3-Clause License @@ -43,6 +43,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/moveit_servo/include/moveit_servo/servo.h b/moveit_ros/moveit_servo/include/moveit_servo/servo.h index 54230ef180..9a5bd2b251 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/servo.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/servo.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /******************************************************************************* * BSD 3-Clause License @@ -43,6 +43,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h b/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h index a0cf4ac37d..362daae0b7 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /******************************************************************************* * BSD 3-Clause License @@ -43,6 +43,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h b/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h index 4a8c3f4d97..46f104dc58 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /******************************************************************************* * BSD 3-Clause License @@ -43,6 +43,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h b/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h index 460c47a3f3..6233947f1c 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /******************************************************************************* * BSD 3-Clause License @@ -43,6 +43,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h b/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h index 78376498db..3140329615 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /******************************************************************************* * BSD 3-Clause License @@ -43,6 +43,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h index 8f10b946d5..b384fcaa74 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h index 331285a793..240fdbd4d8 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h index 4e6036defe..8f2dd40b14 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h b/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h index 8ab969aa8a..cafb8fa91f 100644 --- a/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h +++ b/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h b/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h index 91d58f6a12..f629d7e50c 100644 --- a/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h +++ b/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h index f43b49e58e..500db36df1 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h index 0e22339941..3ee28b68e7 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h index 1ded5abd9e..85e8bbfe28 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h index c71bf3e530..6a31558dae 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h index 5e2bef80eb..f6e5bbcbe6 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h index 9ced6b4634..c0b936c7c9 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h index ce9716f7f0..b5fff07083 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h index 986209a7ac..dca534f033 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h index 2bc38892f7..2151c3a246 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h b/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h index 9306e04440..35a945c3d5 100644 --- a/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h +++ b/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h b/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h index 5f6eacc9d1..df6984b147 100644 --- a/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h +++ b/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h index 39391a7ad0..b85cefaf9c 100644 --- a/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h +++ b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h b/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h index a33b176404..5309e1c1ad 100644 --- a/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h +++ b/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h b/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h index b3a388ecb2..b16bfa71d8 100644 --- a/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h +++ b/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h b/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h index d897dafe26..3e1bef90d8 100644 --- a/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h +++ b/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h index 1ea63e98ac..dfdcdefa72 100644 --- a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h +++ b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -41,6 +41,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h index 1d633e7acd..90b3081009 100644 --- a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h +++ b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -39,6 +39,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h index 49115751d4..f30c6a865d 100644 --- a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h +++ b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h index 0e9fb48650..aa1bd51cf5 100644 --- a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h +++ b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h index ba314e74c9..357c4d6061 100644 --- a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h +++ b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -41,6 +41,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h index 363ca4ad34..4925f7aef0 100644 --- a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -39,6 +39,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h index 7fe30fc6a6..f60b19d863 100644 --- a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -39,6 +39,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h index 2c4ecb6fd3..dee1faf7d4 100644 --- a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -39,6 +39,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h index 117337b8eb..295a7bbd1e 100644 --- a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -39,6 +39,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h index 11835d6a51..1ebb772c30 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h index 85cc67739d..0f00317bbf 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h index 257d2f6965..e398ac2e83 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h index 2a40188131..91fc85fe68 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h index c425308290..0c2b43498e 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h index c34cc1559b..acb5a27b08 100644 --- a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h +++ b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h index 954132d6f1..f811c1f09e 100644 --- a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h +++ b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h b/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h index d7e4795055..b0617f3a89 100644 --- a/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h +++ b/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h index 68546f35ef..3020f01d53 100644 --- a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h +++ b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h b/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h index 09ea5cf002..ed948d909d 100644 --- a/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h +++ b/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h index cdd2780ee1..a49f033319 100644 --- a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h +++ b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -39,6 +39,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h b/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h index 4e3f630a63..99ac52129f 100644 --- a/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h +++ b/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h index 9bf4b94a41..a445e01bd4 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h index c3b89672ba..99df56d4b8 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h index 16d375a33a..def3f8545b 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h index fd78edf07b..28d5c45dff 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h index e3e07515d2..7553074375 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h index 32a954c61b..bc48d66634 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -39,6 +39,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h index 637b67a729..244967960c 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/tests/include/parameter_name_list.h b/moveit_ros/tests/include/parameter_name_list.h index 6516fb09da..4c071f55cd 100644 --- a/moveit_ros/tests/include/parameter_name_list.h +++ b/moveit_ros/tests/include/parameter_name_list.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* @@ -41,6 +41,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h b/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h index 8b02dcd505..aaf77ff561 100644 --- a/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h +++ b/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ // Copyright 2024 Intrinsic Innovation LLC. // @@ -21,6 +21,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h index 2894eadfc9..d928603a19 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /* * Copyright (c) 2008, Willow Garage, Inc. @@ -37,6 +37,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h index 3c61af21a1..325a3a30c7 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h index 55a0b5d7d9..4efd725b98 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h index 24e6233563..e36fa41018 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h index bd6d4be4c5..32e64bb7f9 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h index 0a97984066..4b2a10d015 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h index 2e348c235c..fef4e7011e 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h b/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h index 571595bf08..93b1df35dc 100644 --- a/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h +++ b/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h index 0133c0f163..901dfa5169 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h index 5d0d9c6a33..e879f2534b 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h index 8cdaec5077..ad967f5d61 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h index 0bad8128ce..0441fb18ca 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h index 20514b94a3..7d68af2e61 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h index a7db7d43d0..83d06a9091 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h index 11a861fea0..f6a8982912 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h index 1c3d31eaca..8295effcc1 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /* * Copyright (c) 2008, Willow Garage, Inc. @@ -31,6 +31,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h b/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h index 3df684d154..3f6402c650 100644 --- a/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h +++ b/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -40,6 +40,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h index 66cc4a96d0..4e9ff84484 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h index d14481fd90..a5d21b9000 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h index 6dc98764e2..5fd2042b27 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h index 3ac8369c6d..e1df2b40e8 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h index 563758de8a..048f42bca5 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h index fe52f872ea..e5f4b70113 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h b/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h index 1b1f57cf6c..9dfbca88a1 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h index 13737e29af..205710d87c 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h index 06061aa2a3..ff417e6f5f 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h index 80ab7fee28..9a5ef0a0bd 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h index aa8daa862c..38e46067e8 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h index 6242b5946f..fd0582f839 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h index 57a4362be1..7b5fd8e897 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h index c9d7a3e5f5..9784eac936 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -37,6 +37,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h index 93175b537a..15e7a5a14f 100644 --- a/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h +++ b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h index 4cf63e798f..22ca2ff7fd 100644 --- a/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h +++ b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h index 4033824cb0..665869a7b8 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h index 6ffb6e6d27..d9ae367de6 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -37,6 +37,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h index bbe9b8cbda..198b7a9713 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h index 787dda97c8..7eb943670e 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h index 41805e75a7..eea3c1dbc8 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -37,6 +37,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h index f023c132dc..a980c4b6a7 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h index 4da6d81beb..fee58bf47a 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h index 4bc238fae3..1bebc5bc97 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h index 58b45343bf..574f8d0c68 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h index decc74ea31..21d00e801f 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h index 9dd78d546b..68fbecc70b 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h index 67ad805a8e..e848072d29 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h index 2459b1ffbb..7707257729 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h index 51fd0f784e..b6fb86e80e 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h index e299bc0d5f..54410c9de0 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h index db1d267c88..252de11d4d 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h index 68dd34e168..68a690ea51 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h index 3bd213012a..e324da47a0 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h index 246b8f92a9..749185de92 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h index 45fffa44e1..65f80f4eea 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h index 732b71cb00..f38474b6d0 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h index d628c237a9..2816d1bc7b 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h index a9afd2217e..0c67adb4cb 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -36,6 +36,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h index 536d028e1b..f27b953dc6 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -44,6 +44,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h index 76db21c297..5fa7ea85db 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h index 78145f3d36..532005cd1c 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h index e6e1c55ce4..af430c0544 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h index e416e09207..4417a0d797 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h index db025cfed1..3ebf7c5818 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h index 7a2c6df02c..c26aa3df4a 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h index 6160ade9af..e472803e7a 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h index 66ee7e8e2e..8c2bcaadb2 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h index ec12c2259b..9386df16a8 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h index 4dc2b959a1..e062b68540 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h index c3467f86a0..3b6fd77986 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h index 201201f05a..e48a280259 100644 --- a/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h +++ b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h index bbed9bb99e..b57016a1d0 100644 --- a/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h +++ b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -37,6 +37,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h index 02142729e2..deccbce236 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h index 62714ae047..31bbbc5ea9 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h index 11f0334f2f..9bba621e84 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h index 5c93cc13c0..2d6e42f87a 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h index 2e02d330fe..ed4fe6dd2f 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h index 71ffae597f..f9ae2b62c6 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h index 6005cbb58e..a21b4353cc 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h index 46223fbcaa..554c2d4d0c 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h index 41d953fead..5fb23b1c84 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h index a42cdb850c..55d1a67b3a 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h index 77699ccf93..87218cf548 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h index 0a866ad18e..9e0250cd83 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h index c24e2f1ba4..da20315ff0 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h index dad0658950..934def91a2 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h index d013296060..4b9dfb401c 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h index 73bfa724b7..495db0056e 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h index f4481ca147..c2c9cea422 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h index dc8a162e20..36ccdf32ca 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h index 08d2ec022f..234b7d47da 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h index bec377b4e8..bea4c81ac7 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h @@ -1,4 +1,4 @@ -/* This file was autogenerated by create_deprecated_headers.py +/* This file was autogenerated by create_deprecated_headers.py */ /********************************************************************* * Software License Agreement (BSD License) @@ -38,6 +38,6 @@ #pragma once -/* #pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp") -#include +#include \ No newline at end of file From f2dc4c80fb5ebbc64bc5388b005f805ce8d97173 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Thu, 21 Nov 2024 22:45:05 +0000 Subject: [PATCH 44/53] Applies formatting --- .../allvalid/collision_detector_allocator_allvalid.h | 2 +- .../collision_detection/allvalid/collision_env_allvalid.h | 2 +- .../include/moveit/collision_detection/collision_common.h | 2 +- .../moveit/collision_detection/collision_detector_allocator.h | 2 +- .../include/moveit/collision_detection/collision_env.h | 2 +- .../include/moveit/collision_detection/collision_matrix.h | 2 +- .../moveit/collision_detection/collision_octomap_filter.h | 2 +- .../include/moveit/collision_detection/collision_plugin.h | 2 +- .../moveit/collision_detection/collision_plugin_cache.h | 2 +- .../include/moveit/collision_detection/collision_tools.h | 2 +- .../include/moveit/collision_detection/occupancy_map.h | 2 +- .../moveit/collision_detection/test_collision_common_panda.h | 2 +- .../moveit/collision_detection/test_collision_common_pr2.h | 2 +- .../include/moveit/collision_detection/world.h | 2 +- .../include/moveit/collision_detection/world_diff.h | 2 +- .../bullet_integration/basic_types.h | 2 +- .../bullet_integration/bullet_bvh_manager.h | 2 +- .../bullet_integration/bullet_cast_bvh_manager.h | 2 +- .../bullet_integration/bullet_discrete_bvh_manager.h | 2 +- .../bullet_integration/bullet_utils.h | 2 +- .../bullet_integration/contact_checker_common.h | 2 +- .../bullet_integration/ros_bullet_utils.h | 2 +- .../collision_detector_allocator_bullet.h | 2 +- .../collision_detector_bullet_plugin_loader.h | 2 +- .../moveit/collision_detection_bullet/collision_env_bullet.h | 2 +- .../include/moveit/collision_detection_fcl/collision_common.h | 2 +- .../collision_detection_fcl/collision_detector_allocator_fcl.h | 2 +- .../collision_detector_fcl_plugin_loader.h | 2 +- .../include/moveit/collision_detection_fcl/collision_env_fcl.h | 2 +- .../include/moveit/collision_detection_fcl/fcl_compat.h | 2 +- .../collision_distance_field/collision_common_distance_field.h | 2 +- .../collision_detector_allocator_distance_field.h | 2 +- .../collision_detector_allocator_hybrid.h | 2 +- .../collision_distance_field/collision_distance_field_types.h | 2 +- .../collision_distance_field/collision_env_distance_field.h | 2 +- .../moveit/collision_distance_field/collision_env_hybrid.h | 2 +- .../include/moveit/constraint_samplers/constraint_sampler.h | 2 +- .../moveit/constraint_samplers/constraint_sampler_allocator.h | 2 +- .../moveit/constraint_samplers/constraint_sampler_manager.h | 2 +- .../moveit/constraint_samplers/constraint_sampler_tools.h | 2 +- .../moveit/constraint_samplers/default_constraint_samplers.h | 2 +- .../moveit/constraint_samplers/union_constraint_sampler.h | 2 +- .../include/moveit/controller_manager/controller_manager.h | 2 +- .../include/moveit/distance_field/distance_field.h | 2 +- .../include/moveit/distance_field/find_internal_points.h | 2 +- .../include/moveit/distance_field/propagation_distance_field.h | 2 +- .../distance_field/include/moveit/distance_field/voxel_grid.h | 2 +- .../include/moveit/dynamics_solver/dynamics_solver.h | 2 +- moveit_core/exceptions/include/moveit/exceptions/exceptions.h | 2 +- .../moveit/kinematic_constraints/kinematic_constraint.h | 2 +- .../include/moveit/kinematic_constraints/utils.h | 2 +- .../include/moveit/kinematics_base/kinematics_base.h | 2 +- .../include/moveit/kinematics_metrics/kinematics_metrics.h | 2 +- moveit_core/macros/include/moveit/macros/class_forward.h | 2 +- moveit_core/macros/include/moveit/macros/console_colors.h | 2 +- moveit_core/macros/include/moveit/macros/declare_ptr.h | 2 +- moveit_core/macros/include/moveit/macros/deprecation.h | 2 +- .../moveit/online_signal_smoothing/acceleration_filter.h | 2 +- .../moveit/online_signal_smoothing/butterworth_filter.h | 2 +- .../include/moveit/online_signal_smoothing/ruckig_filter.h | 2 +- .../moveit/online_signal_smoothing/smoothing_base_class.h | 2 +- .../include/moveit/planning_interface/planning_interface.h | 2 +- .../include/moveit/planning_interface/planning_request.h | 2 +- .../moveit/planning_interface/planning_request_adapter.h | 2 +- .../include/moveit/planning_interface/planning_response.h | 2 +- .../moveit/planning_interface/planning_response_adapter.h | 2 +- .../include/moveit/planning_scene/planning_scene.h | 2 +- moveit_core/robot_model/include/moveit/robot_model/aabb.h | 2 +- .../robot_model/include/moveit/robot_model/fixed_joint_model.h | 2 +- .../include/moveit/robot_model/floating_joint_model.h | 2 +- .../robot_model/include/moveit/robot_model/joint_model.h | 2 +- .../robot_model/include/moveit/robot_model/joint_model_group.h | 2 +- .../robot_model/include/moveit/robot_model/link_model.h | 2 +- .../include/moveit/robot_model/planar_joint_model.h | 2 +- .../include/moveit/robot_model/prismatic_joint_model.h | 2 +- .../include/moveit/robot_model/revolute_joint_model.h | 2 +- .../robot_model/include/moveit/robot_model/robot_model.h | 2 +- .../robot_state/include/moveit/robot_state/attached_body.h | 2 +- .../include/moveit/robot_state/cartesian_interpolator.h | 2 +- .../robot_state/include/moveit/robot_state/conversions.h | 2 +- .../robot_state/include/moveit/robot_state/robot_state.h | 2 +- .../include/moveit/robot_trajectory/robot_trajectory.h | 2 +- .../moveit/trajectory_processing/ruckig_traj_smoothing.h | 2 +- .../trajectory_processing/time_optimal_trajectory_generation.h | 2 +- .../moveit/trajectory_processing/time_parameterization.h | 2 +- .../include/moveit/trajectory_processing/trajectory_tools.h | 2 +- moveit_core/transforms/include/moveit/transforms/transforms.h | 2 +- moveit_core/utils/include/moveit/utils/eigen_test_utils.h | 2 +- moveit_core/utils/include/moveit/utils/lexical_casts.h | 2 +- moveit_core/utils/include/moveit/utils/logger.h | 2 +- moveit_core/utils/include/moveit/utils/message_checks.h | 2 +- moveit_core/utils/include/moveit/utils/moveit_error_code.h | 2 +- moveit_core/utils/include/moveit/utils/rclcpp_utils.h | 2 +- .../utils/include/moveit/utils/robot_model_test_utils.h | 2 +- .../cached_ik_kinematics_plugin-inl.h | 2 +- .../cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h | 2 +- .../moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h | 2 +- .../cached_ik_kinematics_plugin/detail/NearestNeighbors.h | 2 +- .../cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h | 2 +- .../moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h | 2 +- .../include/moveit/kdl_kinematics_plugin/joint_mimic.h | 2 +- .../moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h | 2 +- .../moveit/srv_kinematics_plugin/srv_kinematics_plugin.h | 2 +- .../chomp_interface/include/chomp_interface/chomp_interface.h | 2 +- .../include/chomp_interface/chomp_planning_context.h | 2 +- .../include/chomp_motion_planner/chomp_cost.h | 2 +- .../include/chomp_motion_planner/chomp_optimizer.h | 2 +- .../include/chomp_motion_planner/chomp_parameters.h | 2 +- .../include/chomp_motion_planner/chomp_planner.h | 2 +- .../include/chomp_motion_planner/chomp_trajectory.h | 2 +- .../include/chomp_motion_planner/chomp_utils.h | 2 +- .../include/chomp_motion_planner/multivariate_gaussian.h | 2 +- .../moveit/ompl_interface/detail/constrained_goal_sampler.h | 2 +- .../include/moveit/ompl_interface/detail/constrained_sampler.h | 2 +- .../moveit/ompl_interface/detail/constraint_approximations.h | 2 +- .../include/moveit/ompl_interface/detail/constraints_library.h | 2 +- .../include/moveit/ompl_interface/detail/goal_union.h | 2 +- .../include/moveit/ompl_interface/detail/ompl_constraints.h | 2 +- .../moveit/ompl_interface/detail/projection_evaluators.h | 2 +- .../moveit/ompl_interface/detail/state_validity_checker.h | 2 +- .../moveit/ompl_interface/detail/threadsafe_state_storage.h | 2 +- .../moveit/ompl_interface/model_based_planning_context.h | 2 +- .../include/moveit/ompl_interface/ompl_interface.h | 2 +- .../joint_space/constrained_planning_state_space.h | 2 +- .../joint_space/constrained_planning_state_space_factory.h | 2 +- .../parameterization/joint_space/joint_model_state_space.h | 2 +- .../joint_space/joint_model_state_space_factory.h | 2 +- .../ompl_interface/parameterization/model_based_state_space.h | 2 +- .../parameterization/model_based_state_space_factory.h | 2 +- .../parameterization/work_space/pose_model_state_space.h | 2 +- .../work_space/pose_model_state_space_factory.h | 2 +- .../include/moveit/ompl_interface/planning_context_manager.h | 2 +- .../include/joint_limits_copy/joint_limits.h | 2 +- .../include/joint_limits_copy/joint_limits_rosparam.h | 2 +- .../include/pilz_industrial_motion_planner/capability_names.h | 2 +- .../pilz_industrial_motion_planner/cartesian_trajectory.h | 2 +- .../cartesian_trajectory_point.h | 2 +- .../pilz_industrial_motion_planner/command_list_manager.h | 2 +- .../pilz_industrial_motion_planner/joint_limits_aggregator.h | 2 +- .../pilz_industrial_motion_planner/joint_limits_container.h | 2 +- .../pilz_industrial_motion_planner/joint_limits_extension.h | 2 +- .../joint_limits_interface_extension.h | 2 +- .../pilz_industrial_motion_planner/joint_limits_validator.h | 2 +- .../include/pilz_industrial_motion_planner/limits_container.h | 2 +- .../move_group_sequence_action.h | 2 +- .../move_group_sequence_service.h | 2 +- .../pilz_industrial_motion_planner/path_circle_generator.h | 2 +- .../pilz_industrial_motion_planner.h | 2 +- .../pilz_industrial_motion_planner/plan_components_builder.h | 2 +- .../pilz_industrial_motion_planner/planning_context_base.h | 2 +- .../pilz_industrial_motion_planner/planning_context_circ.h | 2 +- .../pilz_industrial_motion_planner/planning_context_lin.h | 2 +- .../pilz_industrial_motion_planner/planning_context_loader.h | 2 +- .../planning_context_loader_circ.h | 2 +- .../planning_context_loader_lin.h | 2 +- .../planning_context_loader_ptp.h | 2 +- .../pilz_industrial_motion_planner/planning_context_ptp.h | 2 +- .../pilz_industrial_motion_planner/planning_exceptions.h | 2 +- .../include/pilz_industrial_motion_planner/tip_frame_getter.h | 2 +- .../pilz_industrial_motion_planner/trajectory_blend_request.h | 2 +- .../pilz_industrial_motion_planner/trajectory_blend_response.h | 2 +- .../pilz_industrial_motion_planner/trajectory_blender.h | 2 +- .../trajectory_blender_transition_window.h | 2 +- .../pilz_industrial_motion_planner/trajectory_functions.h | 2 +- .../trajectory_generation_exceptions.h | 2 +- .../pilz_industrial_motion_planner/trajectory_generator.h | 2 +- .../pilz_industrial_motion_planner/trajectory_generator_circ.h | 2 +- .../pilz_industrial_motion_planner/trajectory_generator_lin.h | 2 +- .../pilz_industrial_motion_planner/trajectory_generator_ptp.h | 2 +- .../pilz_industrial_motion_planner/velocity_profile_atrap.h | 2 +- .../pilz_industrial_motion_planner_testutils/async_test.h | 2 +- .../include/pilz_industrial_motion_planner_testutils/basecmd.h | 2 +- .../cartesianconfiguration.h | 2 +- .../cartesianpathconstraintsbuilder.h | 2 +- .../include/pilz_industrial_motion_planner_testutils/center.h | 2 +- .../include/pilz_industrial_motion_planner_testutils/checks.h | 2 +- .../include/pilz_industrial_motion_planner_testutils/circ.h | 2 +- .../circ_auxiliary_types.h | 2 +- .../pilz_industrial_motion_planner_testutils/circauxiliary.h | 2 +- .../command_types_typedef.h | 2 +- .../pilz_industrial_motion_planner_testutils/default_values.h | 2 +- .../pilz_industrial_motion_planner_testutils/exception_types.h | 2 +- .../goalconstraintsmsgconvertible.h | 2 +- .../include/pilz_industrial_motion_planner_testutils/gripper.h | 2 +- .../include/pilz_industrial_motion_planner_testutils/interim.h | 2 +- .../jointconfiguration.h | 2 +- .../include/pilz_industrial_motion_planner_testutils/lin.h | 2 +- .../pilz_industrial_motion_planner_testutils/motioncmd.h | 2 +- .../motionplanrequestconvertible.h | 2 +- .../include/pilz_industrial_motion_planner_testutils/ptp.h | 2 +- .../robotconfiguration.h | 2 +- .../robotstatemsgconvertible.h | 2 +- .../pilz_industrial_motion_planner_testutils/sequence.h | 2 +- .../pilz_industrial_motion_planner_testutils/testdata_loader.h | 2 +- .../pilz_industrial_motion_planner_testutils/xml_constants.h | 2 +- .../xml_testdata_loader.h | 2 +- .../stomp/include/stomp_moveit/conversion_functions.h | 2 +- moveit_planners/stomp/include/stomp_moveit/cost_functions.h | 2 +- moveit_planners/stomp/include/stomp_moveit/filter_functions.h | 2 +- .../stomp/include/stomp_moveit/math/multivariate_gaussian.h | 2 +- moveit_planners/stomp/include/stomp_moveit/noise_generators.h | 2 +- .../stomp/include/stomp_moveit/stomp_moveit_planning_context.h | 2 +- moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h | 2 +- .../stomp/include/stomp_moveit/trajectory_visualization.h | 2 +- .../include/moveit_ros_control_interface/ControllerHandle.h | 2 +- .../action_based_controller_handle.h | 2 +- .../moveit_simple_controller_manager/empty_controller_handle.h | 2 +- .../follow_joint_trajectory_controller_handle.h | 2 +- .../gripper_controller_handle.h | 2 +- .../include/moveit_py/moveit_py_utils/copy_ros_msg.h | 2 +- .../include/moveit_py/moveit_py_utils/ros_msg_typecasters.h | 2 +- .../benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h | 2 +- .../benchmarks/include/moveit/benchmarks/BenchmarkOptions.h | 2 +- .../include/moveit/global_planner/global_planner_component.h | 2 +- .../include/moveit/global_planner/global_planner_interface.h | 2 +- .../include/moveit/global_planner/moveit_planning_pipeline.h | 2 +- .../moveit/hybrid_planning_manager/hybrid_planning_events.h | 2 +- .../moveit/hybrid_planning_manager/hybrid_planning_manager.h | 2 +- .../moveit/hybrid_planning_manager/planner_logic_interface.h | 2 +- .../planner_logic_plugins/replan_invalidated_trajectory.h | 2 +- .../moveit/planner_logic_plugins/single_plan_execution.h | 2 +- .../local_constraint_solver_plugins/forward_trajectory.h | 2 +- .../include/moveit/local_planner/feedback_types.h | 2 +- .../moveit/local_planner/local_constraint_solver_interface.h | 2 +- .../include/moveit/local_planner/local_planner_component.h | 2 +- .../moveit/local_planner/trajectory_operator_interface.h | 2 +- .../moveit/trajectory_operator_plugins/simple_sampler.h | 2 +- .../move_group/include/moveit/move_group/capability_names.h | 2 +- .../include/moveit/move_group/move_group_capability.h | 2 +- .../move_group/include/moveit/move_group/move_group_context.h | 2 +- .../moveit_servo/include/moveit_servo/collision_monitor.h | 2 +- moveit_ros/moveit_servo/include/moveit_servo/servo.h | 2 +- moveit_ros/moveit_servo/include/moveit_servo/servo_node.h | 2 +- moveit_ros/moveit_servo/include/moveit_servo/utils/command.h | 2 +- moveit_ros/moveit_servo/include/moveit_servo/utils/common.h | 2 +- moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h | 2 +- .../moveit/occupancy_map_monitor/occupancy_map_monitor.h | 2 +- .../occupancy_map_monitor_middleware_handle.h | 2 +- .../moveit/occupancy_map_monitor/occupancy_map_updater.h | 2 +- .../depth_image_octomap_updater/depth_image_octomap_updater.h | 2 +- .../moveit/lazy_free_space_updater/lazy_free_space_updater.h | 2 +- .../include/moveit/mesh_filter/depth_self_filter_nodelet.h | 2 +- .../mesh_filter/include/moveit/mesh_filter/filter_job.h | 2 +- .../mesh_filter/include/moveit/mesh_filter/gl_mesh.h | 2 +- .../mesh_filter/include/moveit/mesh_filter/gl_renderer.h | 2 +- .../mesh_filter/include/moveit/mesh_filter/mesh_filter.h | 2 +- .../mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h | 2 +- .../mesh_filter/include/moveit/mesh_filter/sensor_model.h | 2 +- .../include/moveit/mesh_filter/stereo_camera_model.h | 2 +- .../include/moveit/mesh_filter/transform_provider.h | 2 +- .../include/moveit/point_containment_filter/shape_mask.h | 2 +- .../pointcloud_octomap_updater/pointcloud_octomap_updater.h | 2 +- .../include/moveit/semantic_world/semantic_world.h | 2 +- .../moveit/collision_plugin_loader/collision_plugin_loader.h | 2 +- .../constraint_sampler_manager_loader.h | 2 +- .../moveit/kinematics_plugin_loader/kinematics_plugin_loader.h | 2 +- .../planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h | 2 +- .../moveit_cpp/include/moveit/moveit_cpp/planning_component.h | 2 +- .../include/moveit/plan_execution/plan_execution.h | 2 +- .../include/moveit/plan_execution/plan_representation.h | 2 +- .../include/moveit/planning_pipeline/planning_pipeline.h | 2 +- .../planning_pipeline_interfaces/plan_responses_container.h | 2 +- .../planning_pipeline_interfaces.h | 2 +- .../solution_selection_functions.h | 2 +- .../stopping_criterion_functions.h | 2 +- .../moveit/planning_scene_monitor/current_state_monitor.h | 2 +- .../current_state_monitor_middleware_handle.h | 2 +- .../moveit/planning_scene_monitor/planning_scene_monitor.h | 2 +- .../include/moveit/planning_scene_monitor/trajectory_monitor.h | 2 +- .../trajectory_monitor_middleware_handle.h | 2 +- .../planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h | 2 +- .../include/moveit/rdf_loader/synchronized_string_parameter.h | 2 +- .../include/moveit/robot_model_loader/robot_model_loader.h | 2 +- .../trajectory_execution_manager.h | 2 +- .../moveit/common_planning_interface_objects/common_objects.h | 2 +- .../include/moveit/move_group_interface/move_group_interface.h | 2 +- .../moveit/planning_scene_interface/planning_scene_interface.h | 2 +- .../include/moveit/robot_interaction/interaction.h | 2 +- .../include/moveit/robot_interaction/interaction_handler.h | 2 +- .../moveit/robot_interaction/interactive_marker_helpers.h | 2 +- .../include/moveit/robot_interaction/kinematic_options.h | 2 +- .../include/moveit/robot_interaction/kinematic_options_map.h | 2 +- .../include/moveit/robot_interaction/locked_robot_state.h | 2 +- .../include/moveit/robot_interaction/robot_interaction.h | 2 +- moveit_ros/tests/include/parameter_name_list.h | 3 +-- .../include/moveit/trajectory_cache/trajectory_cache.h | 2 +- .../motion_planning_rviz_plugin/interactive_marker_display.h | 2 +- .../motion_planning_rviz_plugin/motion_planning_display.h | 2 +- .../moveit/motion_planning_rviz_plugin/motion_planning_frame.h | 2 +- .../motion_planning_frame_joints_widget.h | 2 +- .../motion_planning_rviz_plugin/motion_planning_param_widget.h | 2 +- .../moveit/planning_scene_rviz_plugin/background_processing.h | 2 +- .../moveit/planning_scene_rviz_plugin/planning_scene_display.h | 2 +- .../moveit/robot_state_rviz_plugin/robot_state_display.h | 2 +- .../include/moveit/rviz_plugin_render_tools/octomap_render.h | 2 +- .../moveit/rviz_plugin_render_tools/planning_link_updater.h | 2 +- .../moveit/rviz_plugin_render_tools/planning_scene_render.h | 2 +- .../include/moveit/rviz_plugin_render_tools/render_shapes.h | 2 +- .../rviz_plugin_render_tools/robot_state_visualization.h | 2 +- .../include/moveit/rviz_plugin_render_tools/trajectory_panel.h | 2 +- .../moveit/rviz_plugin_render_tools/trajectory_visualization.h | 2 +- .../rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h | 2 +- .../include/moveit/trajectory_rviz_plugin/trajectory_display.h | 2 +- .../warehouse/include/moveit/warehouse/constraints_storage.h | 2 +- .../include/moveit/warehouse/moveit_message_storage.h | 2 +- .../include/moveit/warehouse/planning_scene_storage.h | 2 +- .../include/moveit/warehouse/planning_scene_world_storage.h | 2 +- moveit_ros/warehouse/include/moveit/warehouse/state_storage.h | 2 +- .../include/moveit/warehouse/trajectory_constraints_storage.h | 2 +- .../warehouse/include/moveit/warehouse/warehouse_connector.h | 2 +- .../include/moveit_setup_app_plugins/launch_bundle.h | 2 +- .../include/moveit_setup_app_plugins/launches.h | 2 +- .../include/moveit_setup_app_plugins/launches_config.h | 2 +- .../include/moveit_setup_app_plugins/launches_widget.h | 2 +- .../include/moveit_setup_app_plugins/perception.h | 2 +- .../include/moveit_setup_app_plugins/perception_config.h | 2 +- .../include/moveit_setup_app_plugins/perception_widget.h | 2 +- .../include/moveit_setup_assistant/navigation_widget.h | 2 +- .../include/moveit_setup_assistant/setup_assistant_widget.h | 2 +- .../include/moveit_setup_controllers/control_xacro_config.h | 2 +- .../include/moveit_setup_controllers/controller_edit_widget.h | 2 +- .../include/moveit_setup_controllers/controllers.h | 2 +- .../include/moveit_setup_controllers/controllers_config.h | 2 +- .../include/moveit_setup_controllers/controllers_widget.h | 2 +- .../include/moveit_setup_controllers/included_xacro_config.h | 2 +- .../include/moveit_setup_controllers/modified_urdf_config.h | 2 +- .../include/moveit_setup_controllers/moveit_controllers.h | 2 +- .../moveit_setup_controllers/moveit_controllers_config.h | 2 +- .../include/moveit_setup_controllers/ros2_controllers.h | 2 +- .../include/moveit_setup_controllers/ros2_controllers_config.h | 2 +- .../include/moveit_setup_controllers/urdf_modifications.h | 2 +- .../moveit_setup_controllers/urdf_modifications_widget.h | 2 +- .../include/moveit_setup_core_plugins/author_information.h | 2 +- .../moveit_setup_core_plugins/author_information_widget.h | 2 +- .../include/moveit_setup_core_plugins/configuration_files.h | 2 +- .../moveit_setup_core_plugins/configuration_files_widget.h | 2 +- .../include/moveit_setup_core_plugins/start_screen.h | 2 +- .../include/moveit_setup_core_plugins/start_screen_widget.h | 2 +- .../include/moveit_setup_framework/config.h | 2 +- .../moveit_setup_framework/data/package_settings_config.h | 2 +- .../include/moveit_setup_framework/data/srdf_config.h | 2 +- .../include/moveit_setup_framework/data/urdf_config.h | 2 +- .../include/moveit_setup_framework/data_warehouse.h | 2 +- .../include/moveit_setup_framework/generated_file.h | 2 +- .../include/moveit_setup_framework/generated_time.h | 2 +- .../include/moveit_setup_framework/qt/double_list_widget.h | 2 +- .../include/moveit_setup_framework/qt/helper_widgets.h | 2 +- .../include/moveit_setup_framework/qt/rviz_panel.h | 2 +- .../include/moveit_setup_framework/qt/setup_step_widget.h | 2 +- .../include/moveit_setup_framework/qt/xml_syntax_highlighter.h | 2 +- .../include/moveit_setup_framework/setup_step.h | 2 +- .../include/moveit_setup_framework/templates.h | 2 +- .../include/moveit_setup_framework/testing_utils.h | 2 +- .../include/moveit_setup_framework/utilities.h | 2 +- .../include/moveit_setup_simulation/simulation.h | 2 +- .../include/moveit_setup_simulation/simulation_widget.h | 2 +- .../include/moveit_setup_srdf_plugins/collision_linear_model.h | 2 +- .../include/moveit_setup_srdf_plugins/collision_matrix_model.h | 2 +- .../moveit_setup_srdf_plugins/compute_default_collisions.h | 2 +- .../include/moveit_setup_srdf_plugins/default_collisions.h | 2 +- .../moveit_setup_srdf_plugins/default_collisions_widget.h | 2 +- .../include/moveit_setup_srdf_plugins/end_effectors.h | 2 +- .../include/moveit_setup_srdf_plugins/end_effectors_widget.h | 2 +- .../include/moveit_setup_srdf_plugins/group_edit_widget.h | 2 +- .../include/moveit_setup_srdf_plugins/group_meta_config.h | 2 +- .../include/moveit_setup_srdf_plugins/kinematic_chain_widget.h | 2 +- .../include/moveit_setup_srdf_plugins/passive_joints.h | 2 +- .../include/moveit_setup_srdf_plugins/passive_joints_widget.h | 2 +- .../include/moveit_setup_srdf_plugins/planning_groups.h | 2 +- .../include/moveit_setup_srdf_plugins/planning_groups_widget.h | 2 +- .../include/moveit_setup_srdf_plugins/robot_poses.h | 2 +- .../include/moveit_setup_srdf_plugins/robot_poses_widget.h | 2 +- .../include/moveit_setup_srdf_plugins/rotated_header_view.h | 2 +- .../include/moveit_setup_srdf_plugins/srdf_step.h | 2 +- .../include/moveit_setup_srdf_plugins/virtual_joints.h | 2 +- .../include/moveit_setup_srdf_plugins/virtual_joints_widget.h | 2 +- 376 files changed, 376 insertions(+), 377 deletions(-) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h index 46a87f0e7f..2cc400ec92 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h index 8057b05872..869861d7a9 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h index 99a2a3e43b..9ceb56b066 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h index 4af6061a5c..c28acf0993 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h index bf1c537381..529c8cefc4 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h index 6b3eec200d..cd1a720d32 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h index a681964d85..5b86596d41 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h index ed27b3349b..6833d7c26a 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h index ee023950a2..fc446ddcbf 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h index ec0c4ad0e5..4fa1eb74fe 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h b/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h index 77079b51b9..8c0c8ada8b 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h index a84fb9d799..496df6ceee 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h index 55bcf1a7e1..9e9c787de8 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/world.h b/moveit_core/collision_detection/include/moveit/collision_detection/world.h index d4428b00bb..9c5d42560d 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/world.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/world.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h b/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h index dff078f69a..23b2eb1716 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h index 3210a0d419..f62361dba0 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h @@ -24,4 +24,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h index 8ea976e4b8..e05390b07f 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h @@ -37,4 +37,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h index 1604585f5c..8c127c4e2a 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h @@ -37,4 +37,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h index 95288fec1d..ff7c5b9784 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h @@ -37,4 +37,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h index 9e1d841602..1a65f42407 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h index 9f96fb1404..117e76edb0 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h @@ -24,4 +24,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h index 05e155d59f..c0ed859038 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h @@ -24,4 +24,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h index e18cdb7650..b11de1d5d8 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h index d0c46b607b..884361bce3 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h index 03fe11fac5..86c03d067d 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h index 61243ca3f5..b37ad61329 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h index c0349364dc..4d14c990e3 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h index de1966c28b..65a42060cd 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h index 04146056a3..cdf1ac8f7b 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h index f353a6ae24..6a0e33c5a8 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h index 0f601d4fcf..b3c60923ff 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h index adf9fd35d3..56dab33c44 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h index bb3aafbd3a..9e2ceb047d 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h index 87f7574861..a0eb0b5bc5 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h index a077c1be79..14262748c0 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h index 1dbe760be3..33d61d0095 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h index ac88859f01..74b8c2f5c1 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h index 662f649868..361301a2c7 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h index 99a669dcf3..a2967ad216 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h index d5f8ffd2a4..941149b085 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h index 76f739d855..2d827d79a1 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h index 1ab75af0b7..eb66c58e1f 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h b/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h index f1ae07e744..d755079e4d 100644 --- a/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h +++ b/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/distance_field/include/moveit/distance_field/distance_field.h b/moveit_core/distance_field/include/moveit/distance_field/distance_field.h index 9ed8e2a4b4..175aa0660e 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/distance_field.h +++ b/moveit_core/distance_field/include/moveit/distance_field/distance_field.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h b/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h index 1d4fe0ffd8..5d78049852 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h +++ b/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h b/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h index 901891c127..467304bcff 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h +++ b/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h b/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h index 25a4185324..5cb57e8b5e 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h +++ b/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h b/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h index 3af00567ad..bc029f70a1 100644 --- a/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h +++ b/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/exceptions/include/moveit/exceptions/exceptions.h b/moveit_core/exceptions/include/moveit/exceptions/exceptions.h index 58b97119eb..f5255844d5 100644 --- a/moveit_core/exceptions/include/moveit/exceptions/exceptions.h +++ b/moveit_core/exceptions/include/moveit/exceptions/exceptions.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h index e4458b541b..da3c805561 100644 --- a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h +++ b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h index e4937b10bf..9d53853999 100644 --- a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h +++ b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h index 2a7966c4b7..0b9e9b5c18 100644 --- a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h +++ b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h b/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h index 29392d6013..c0bfdcb5a4 100644 --- a/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h +++ b/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/macros/include/moveit/macros/class_forward.h b/moveit_core/macros/include/moveit/macros/class_forward.h index 615708cc9e..0672af5f0e 100644 --- a/moveit_core/macros/include/moveit/macros/class_forward.h +++ b/moveit_core/macros/include/moveit/macros/class_forward.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/macros/include/moveit/macros/console_colors.h b/moveit_core/macros/include/moveit/macros/console_colors.h index 9098a338f6..d3caa6fa54 100644 --- a/moveit_core/macros/include/moveit/macros/console_colors.h +++ b/moveit_core/macros/include/moveit/macros/console_colors.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/macros/include/moveit/macros/declare_ptr.h b/moveit_core/macros/include/moveit/macros/declare_ptr.h index 586a142d33..95c4553e8d 100644 --- a/moveit_core/macros/include/moveit/macros/declare_ptr.h +++ b/moveit_core/macros/include/moveit/macros/declare_ptr.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/macros/include/moveit/macros/deprecation.h b/moveit_core/macros/include/moveit/macros/deprecation.h index b0b6670cdd..378ee33607 100644 --- a/moveit_core/macros/include/moveit/macros/deprecation.h +++ b/moveit_core/macros/include/moveit/macros/deprecation.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h index a3010df82d..c0fa16deb0 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h @@ -76,4 +76,4 @@ c --------x--- v | #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h index fef50eb661..283e3c73dd 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h @@ -43,4 +43,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h index 3ebd65db48..191dd9ac6a 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h @@ -42,4 +42,4 @@ Description: Applies jerk/acceleration/velocity limits to online motion commands #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h index e165d715f5..76312e06f1 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h @@ -42,4 +42,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h index d57a887b2e..1ec25f02c5 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h index 385f27b52c..f7f1fb90e1 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h index 3613557f18..c4d213da6e 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h @@ -42,4 +42,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h index 877b1c1bfb..3719729058 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h index a7dd1ebd4b..a5aef5018d 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h index acd09c66ed..971c48b105 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/robot_model/include/moveit/robot_model/aabb.h b/moveit_core/robot_model/include/moveit/robot_model/aabb.h index 20ed6d0e80..a0a27d69bc 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/aabb.h +++ b/moveit_core/robot_model/include/moveit/robot_model/aabb.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h index f9788be573..0f75393809 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h index 1f25091581..8bbfdc48e4 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/robot_model/include/moveit/robot_model/joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/joint_model.h index c70ec2e7eb..068b57b256 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/joint_model.h @@ -41,4 +41,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h index 1c572d8efd..d8ee3e7d7f 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h +++ b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h @@ -41,4 +41,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/robot_model/include/moveit/robot_model/link_model.h b/moveit_core/robot_model/include/moveit/robot_model/link_model.h index b1b8d564ac..b51bfdea1f 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/link_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/link_model.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h index 309ba8d001..3012f330b5 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h index 792ff303fb..26a33af320 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h index 1071b25a3e..2298b04313 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h index 947087c152..f3b542586f 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h @@ -41,4 +41,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/robot_state/include/moveit/robot_state/attached_body.h b/moveit_core/robot_state/include/moveit/robot_state/attached_body.h index 30ea3b015a..5f5da7f9bc 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/attached_body.h +++ b/moveit_core/robot_state/include/moveit/robot_state/attached_body.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h b/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h index 361f9e1882..70c2b68fb7 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h +++ b/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h @@ -42,4 +42,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/robot_state/include/moveit/robot_state/conversions.h b/moveit_core/robot_state/include/moveit/robot_state/conversions.h index c6b6e0b0f0..9ac01e17ea 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/conversions.h +++ b/moveit_core/robot_state/include/moveit/robot_state/conversions.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h index c6b1e98a0b..64fcd4ad52 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h +++ b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h @@ -41,4 +41,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h index d8b6a64c5d..a1be2291e0 100644 --- a/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h +++ b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h index a4bb2cf573..a56508c0c2 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h @@ -39,4 +39,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h index 7adb051d78..a1763bb4c0 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h @@ -42,4 +42,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h index 9f5fb81801..4d6163c289 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h @@ -4,4 +4,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h index 344e24f289..1ad1d58c74 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/transforms/include/moveit/transforms/transforms.h b/moveit_core/transforms/include/moveit/transforms/transforms.h index 63a657e0fd..21f6f7152e 100644 --- a/moveit_core/transforms/include/moveit/transforms/transforms.h +++ b/moveit_core/transforms/include/moveit/transforms/transforms.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/utils/include/moveit/utils/eigen_test_utils.h b/moveit_core/utils/include/moveit/utils/eigen_test_utils.h index 5bc646070d..502de6298b 100644 --- a/moveit_core/utils/include/moveit/utils/eigen_test_utils.h +++ b/moveit_core/utils/include/moveit/utils/eigen_test_utils.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/utils/include/moveit/utils/lexical_casts.h b/moveit_core/utils/include/moveit/utils/lexical_casts.h index 4b3763a561..df163601bd 100644 --- a/moveit_core/utils/include/moveit/utils/lexical_casts.h +++ b/moveit_core/utils/include/moveit/utils/lexical_casts.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/utils/include/moveit/utils/logger.h b/moveit_core/utils/include/moveit/utils/logger.h index 8407c8d060..19afba16aa 100644 --- a/moveit_core/utils/include/moveit/utils/logger.h +++ b/moveit_core/utils/include/moveit/utils/logger.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/utils/include/moveit/utils/message_checks.h b/moveit_core/utils/include/moveit/utils/message_checks.h index ffdee74e59..4acd7a0b76 100644 --- a/moveit_core/utils/include/moveit/utils/message_checks.h +++ b/moveit_core/utils/include/moveit/utils/message_checks.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/utils/include/moveit/utils/moveit_error_code.h b/moveit_core/utils/include/moveit/utils/moveit_error_code.h index 93eb88b1bb..c581490398 100644 --- a/moveit_core/utils/include/moveit/utils/moveit_error_code.h +++ b/moveit_core/utils/include/moveit/utils/moveit_error_code.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/utils/include/moveit/utils/rclcpp_utils.h b/moveit_core/utils/include/moveit/utils/rclcpp_utils.h index 91bdb167a0..50b40c0578 100644 --- a/moveit_core/utils/include/moveit/utils/rclcpp_utils.h +++ b/moveit_core/utils/include/moveit/utils/rclcpp_utils.h @@ -31,4 +31,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h b/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h index 87eb4622bb..d158b356b6 100644 --- a/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h +++ b/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h @@ -41,4 +41,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h index fa310d550c..487fa7b11a 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h index 3587f2ed3f..334e836730 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h index 031f15d265..32969443b4 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h @@ -42,4 +42,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h index d0c5be3032..63ca8d785f 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h @@ -42,4 +42,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h index efb6068acf..04a8bf2338 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h @@ -42,4 +42,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h index 4e0cad00c7..0b0eadcc2d 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h +++ b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h @@ -29,4 +29,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h index 0808dc431b..12d8d6b63b 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h +++ b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h index 367f77b5ce..cef3bac3a3 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h +++ b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h b/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h index c8f0df3a5a..fb254f56d9 100644 --- a/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h +++ b/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h @@ -45,4 +45,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h index baa38800f8..49801844d3 100644 --- a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h +++ b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h index 2d6884e485..5f3549706d 100644 --- a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h +++ b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h index 0bab0ca82d..a94ebd67b9 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h index cccdf40aec..5db2c5fffa 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h index 6baab5f32e..838652f3fa 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h @@ -43,4 +43,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h index be79d1b6f9..9bea627d9a 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h index 70d54639c4..9f40c14523 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h index 6bd816a0a9..fb7100ec1c 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h index 554bd1f31b..68b8e8c4a3 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h index 71e03612e6..4a8a19ef13 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h index e62686e8dc..76b2b41cbc 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h index 0aa71101fa..ed41697b8d 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h index dc47c60535..8e95035359 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h index 9f0c221973..20c672ba95 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h index 9a11b88e57..f7f297c63b 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h index 1f401618a7..f397b1db06 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h index a7be4cc1f0..2ab0209014 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h @@ -51,4 +51,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h index 1f1c3373e8..ae49ac9319 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h index a99c2cb84b..86320a9b48 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h index f3fc050205..333eabd246 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h index 04acc05227..beaad450d0 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h index 233f11f42e..9b4fce28e8 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h @@ -41,4 +41,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h index ee2426f442..ab411e16cf 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h index 267a3bbc31..1c6177a1a6 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h index 9ad24a8e20..08b72799a7 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h index 37a74cd90e..57c5e71527 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h index b38741bd6a..ae5d49300e 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h index 9d56e5136f..9ac5e8f08f 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h index 5ffa3ca325..1b08d92ffa 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h index a5b37be196..86aa0b2489 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h @@ -20,4 +20,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h index e6f335a70d..0b01801bd8 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h @@ -20,4 +20,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h index 0ca1157de7..623cf5d388 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h index 324a0931e2..cf993e9597 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h index ca7664a0ea..27148547b2 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h index d0f14a23f4..2119cf8d4f 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h index d4932cd523..f897cdcb9f 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h index cdd6eaf316..be11f04abe 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h index a9f5c554c5..90cf4c05bc 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h index a860842eab..334c6b8541 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h index cefd648053..1a7b2cc4cf 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h index c902fd4f9d..f7313c7da6 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h index 508d435714..9e2636131e 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h index 76c02d2e4a..7b1030ff55 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h index b8d16394cf..39c43daea0 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h index bd6de3e652..cdf2e089f9 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h index a8cbf2b4ea..2d3c856904 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h index 27618d49bb..d25357116b 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h index dbe4d6a1c9..cf489f1ad2 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h index e551197760..7e6fb14cc2 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h index 01527922f2..5561b7e96c 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h index 12842205e5..550f50ab96 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h index 1f8293a003..5474966315 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h index 7c963ca0c7..eb03da07e6 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h index 84cd985367..d01c4464ca 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h index 4d6d3d2511..f1c7882c70 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h index 868b04e540..a9f036615a 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h index 3ffac85bc7..67f84dc688 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h index 9dec1b249a..132b6dbbf8 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h index 892bc4ce00..7ebf68b68a 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h index a8c09c0ea1..deffe14550 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h index 8cbdf117f3..520984cf13 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h index 0404071c27..b89d6952db 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h index 5abcd0c63c..80ec42dd58 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h index 69605940dd..3dab1fe486 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h index 05c34019b7..95316e909f 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h index b157842300..4f62103dfe 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h index d315ec8904..01624f4946 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h index 98306c8bc3..bd2e6a6013 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h @@ -20,4 +20,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h index 8988d2ea9a..d263360e51 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h index 4ffdf6e663..561dfa0848 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h index 2adda44dc9..c32220b13b 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h index f445bc2c76..5ffd3fcd48 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h index 07ed9cab4f..806e89d721 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h index dffcead493..a05fc27433 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h index 4cb20c1af6..12d68b9af0 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h index ffa7831cd5..5546efbfec 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h index 5ef7daa238..61bb944fc1 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h index 34728d78b1..2c8a36a27f 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h index e0935a4515..4edd1d6368 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h index 193fa060f8..16105a1888 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h index 96e1267f58..ed40838e5c 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h index b70c46a3e1..05710f0786 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h index 7ff3b797eb..981dbb66ef 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h index 3fc8bdeffc..1b82054e20 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h index 5e68328b51..76b9eabbed 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h index 75df8d156e..ba09ebc5df 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h index 3e85b02371..7cbb25b11b 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h index a9538c04c8..d0e6cc7951 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h index d6b96e7e62..2a6420b046 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h index 8ab1962490..dbfc6831c3 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h index 95eac3f7a4..03eaef20bf 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h index 7cc6f879cf..4ac7e23e8d 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h index 90f190f887..ab693267e7 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h b/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h index a3af845723..c4353b19ad 100644 --- a/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h +++ b/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h @@ -43,4 +43,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/stomp/include/stomp_moveit/cost_functions.h b/moveit_planners/stomp/include/stomp_moveit/cost_functions.h index 7c7418c929..26d5bb757a 100644 --- a/moveit_planners/stomp/include/stomp_moveit/cost_functions.h +++ b/moveit_planners/stomp/include/stomp_moveit/cost_functions.h @@ -43,4 +43,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/stomp/include/stomp_moveit/filter_functions.h b/moveit_planners/stomp/include/stomp_moveit/filter_functions.h index b6ef586b3f..8afe0d34f9 100644 --- a/moveit_planners/stomp/include/stomp_moveit/filter_functions.h +++ b/moveit_planners/stomp/include/stomp_moveit/filter_functions.h @@ -43,4 +43,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h b/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h index 92d0659e7b..e94f9a9445 100644 --- a/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h +++ b/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h @@ -43,4 +43,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/stomp/include/stomp_moveit/noise_generators.h b/moveit_planners/stomp/include/stomp_moveit/noise_generators.h index 80b341b660..e84a3217d0 100644 --- a/moveit_planners/stomp/include/stomp_moveit/noise_generators.h +++ b/moveit_planners/stomp/include/stomp_moveit/noise_generators.h @@ -43,4 +43,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h index 5bb31068fa..3e217e6ec2 100644 --- a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h +++ b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h @@ -43,4 +43,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h index 822b645faa..3dc922cdcb 100644 --- a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h +++ b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h @@ -58,4 +58,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h b/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h index aef2acf719..182a568121 100644 --- a/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h +++ b/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h @@ -43,4 +43,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h b/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h index 309076cfe4..72b32af6f0 100644 --- a/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h +++ b/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h index 69b4e45ec7..f7d654a8f5 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h @@ -41,4 +41,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h index bd08d3f4ba..dbff9094ac 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h index 59bcce52a2..4d25d743ec 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h @@ -41,4 +41,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h index a64afec097..960ca9f9b5 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h @@ -41,4 +41,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h index ebf4587a4f..f215dc1201 100644 --- a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h +++ b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h index ee94381a75..7696f68a70 100644 --- a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h +++ b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h index 60445cd82c..0dcd0aaf0e 100644 --- a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h +++ b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h index 8a6b08b4a1..07ba256b94 100644 --- a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h +++ b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h index 6b10c6f8e7..d73b113f41 100644 --- a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h +++ b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h @@ -42,4 +42,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h index 2b35e0e598..796c340767 100644 --- a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h +++ b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h @@ -43,4 +43,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h b/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h index 57d8b775a6..ece0b29165 100644 --- a/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h +++ b/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h @@ -41,4 +41,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h index 0d01adf237..bd171df69c 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h @@ -41,4 +41,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h index bec1a489cd..4e86535a5c 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h @@ -42,4 +42,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h index 3b780bf65d..45183839ce 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h @@ -42,4 +42,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h index 00a1d61858..82caf35cec 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h @@ -44,4 +44,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h index 119b5e4922..ce07623ad8 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h @@ -43,4 +43,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h b/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h index 9450b37538..3700846a34 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h +++ b/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h @@ -44,4 +44,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h index 63cb254fa4..53dc4f1fa2 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h @@ -43,4 +43,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h index bd5aa4f9ac..a292f6163a 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h @@ -42,4 +42,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h index 4a76087904..230c1cd5db 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h @@ -43,4 +43,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h index 502de4c984..6331ed1930 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h @@ -42,4 +42,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h b/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h index b00d9f7118..d6594245cc 100644 --- a/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h +++ b/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h @@ -44,4 +44,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/move_group/include/moveit/move_group/capability_names.h b/moveit_ros/move_group/include/moveit/move_group/capability_names.h index d0ed41a3b7..efa01718d0 100644 --- a/moveit_ros/move_group/include/moveit/move_group/capability_names.h +++ b/moveit_ros/move_group/include/moveit/move_group/capability_names.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h b/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h index 93b08bda72..309771bed6 100644 --- a/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h +++ b/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/move_group/include/moveit/move_group/move_group_context.h b/moveit_ros/move_group/include/moveit/move_group/move_group_context.h index 28377b4854..8a815d0803 100644 --- a/moveit_ros/move_group/include/moveit/move_group/move_group_context.h +++ b/moveit_ros/move_group/include/moveit/move_group/move_group_context.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h b/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h index 8b7887c43e..39ee60647a 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h @@ -45,4 +45,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/servo.h b/moveit_ros/moveit_servo/include/moveit_servo/servo.h index 9a5bd2b251..5c2775a6c9 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/servo.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/servo.h @@ -45,4 +45,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h b/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h index 362daae0b7..ed0613b831 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h @@ -45,4 +45,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h b/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h index 46f104dc58..1be5adb12d 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h @@ -45,4 +45,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h b/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h index 6233947f1c..1d71f5f93d 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h @@ -45,4 +45,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h b/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h index 3140329615..077a08857f 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h @@ -45,4 +45,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h index b384fcaa74..15ce4d9157 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h index 240fdbd4d8..590414dff2 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h index 8f2dd40b14..08d76f4d40 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h b/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h index cafb8fa91f..ad3200955d 100644 --- a/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h +++ b/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h b/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h index f629d7e50c..793ebdb82a 100644 --- a/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h +++ b/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h index 500db36df1..6773febabb 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h index 3ee28b68e7..81bad2aba0 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h index 85e8bbfe28..10da7fc760 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h index 6a31558dae..ae243007d3 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h index f6e5bbcbe6..0a6467dad1 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h index c0b936c7c9..38e5235d5f 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h index b5fff07083..d20606a7f5 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h index dca534f033..94b9921780 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h index 2151c3a246..5a5a5b7542 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h b/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h index 35a945c3d5..b932008ffc 100644 --- a/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h +++ b/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h b/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h index df6984b147..4867721c0a 100644 --- a/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h +++ b/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h index b85cefaf9c..f70bae33d6 100644 --- a/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h +++ b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h b/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h index 5309e1c1ad..333778f9ad 100644 --- a/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h +++ b/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h b/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h index b16bfa71d8..f3d080bf1a 100644 --- a/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h +++ b/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h b/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h index 3e1bef90d8..02dca8cabb 100644 --- a/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h +++ b/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h index dfdcdefa72..4f9e19dc48 100644 --- a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h +++ b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h @@ -43,4 +43,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h index 90b3081009..3f90593721 100644 --- a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h +++ b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h @@ -41,4 +41,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h index f30c6a865d..4aab5668c1 100644 --- a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h +++ b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h index aa1bd51cf5..18119f94c1 100644 --- a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h +++ b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h index 357c4d6061..8879080882 100644 --- a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h +++ b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h @@ -43,4 +43,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h index 4925f7aef0..de4e9f719e 100644 --- a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h @@ -41,4 +41,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h index f60b19d863..c01195ca4e 100644 --- a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h @@ -41,4 +41,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h index dee1faf7d4..35ce8911e0 100644 --- a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h @@ -41,4 +41,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h index 295a7bbd1e..d372a72e04 100644 --- a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h @@ -41,4 +41,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h index 1ebb772c30..79beb2562f 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h index 0f00317bbf..80ecf0d023 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h index e398ac2e83..93baee4489 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h index 91fc85fe68..1cd008cbac 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h index 0c2b43498e..91c9711f52 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h index acb5a27b08..4640cfbf8c 100644 --- a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h +++ b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h index f811c1f09e..98b4e0052d 100644 --- a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h +++ b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h b/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h index b0617f3a89..ca4b221d14 100644 --- a/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h +++ b/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h index 3020f01d53..770bc32b92 100644 --- a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h +++ b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h b/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h index ed948d909d..70fce5a27e 100644 --- a/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h +++ b/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h index a49f033319..f618e290ba 100644 --- a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h +++ b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h @@ -41,4 +41,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h b/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h index 99ac52129f..425f85dc32 100644 --- a/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h +++ b/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h index a445e01bd4..26cf97bf31 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h index 99df56d4b8..179c0a9e1c 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h index def3f8545b..cd626080cb 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h index 28d5c45dff..7900d8afed 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h index 7553074375..eb2a9ac367 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h index bc48d66634..d879bd8b24 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h @@ -41,4 +41,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h index 244967960c..2acb62a7e6 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/tests/include/parameter_name_list.h b/moveit_ros/tests/include/parameter_name_list.h index 4c071f55cd..d7cc404d13 100644 --- a/moveit_ros/tests/include/parameter_name_list.h +++ b/moveit_ros/tests/include/parameter_name_list.h @@ -1,6 +1,5 @@ /* This file was autogenerated by create_deprecated_headers.py */ - /********************************************************************* * Software License Agreement (BSD License) * @@ -43,4 +42,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h b/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h index aaf77ff561..d049693521 100644 --- a/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h +++ b/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h @@ -23,4 +23,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h index d928603a19..b20d10517d 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h @@ -39,4 +39,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h index 325a3a30c7..fb92f6098f 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h index 4efd725b98..006cc0c842 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h index e36fa41018..3ad72683f2 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h index 32e64bb7f9..b5854d836f 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h index 4b2a10d015..65cdc806d5 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h index fef4e7011e..d9572c06ad 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h b/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h index 93b1df35dc..f7b7b0179d 100644 --- a/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h +++ b/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h index 901dfa5169..1129ce07a2 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h index e879f2534b..d1eae788e3 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h index ad967f5d61..dea106ee87 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h index 0441fb18ca..03605fe053 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h index 7d68af2e61..6959add96d 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h index 83d06a9091..c9f41a8e49 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h index f6a8982912..d1e5943aa6 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h index 8295effcc1..2f33de77b8 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h @@ -33,4 +33,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h b/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h index 3f6402c650..052ec279d4 100644 --- a/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h +++ b/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h @@ -42,4 +42,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h index 4e9ff84484..6d340a3893 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h index a5d21b9000..4d7c3237af 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h index 5fd2042b27..ab7d4ddb73 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h index e1df2b40e8..029914de5e 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h index 048f42bca5..64fe81fac3 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h index e5f4b70113..9ab4a54d4a 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h b/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h index 9dfbca88a1..be72e8fea0 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h index 205710d87c..300da2d8b1 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h @@ -39,4 +39,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h index ff417e6f5f..6932f018fe 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h @@ -39,4 +39,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h index 9a5ef0a0bd..1281141665 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h @@ -39,4 +39,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h index 38e46067e8..3381af5951 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h @@ -39,4 +39,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h index fd0582f839..b9e2282fc3 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h @@ -39,4 +39,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h index 7b5fd8e897..ef4007385c 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h @@ -39,4 +39,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h index 9784eac936..c4a0f45dec 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h @@ -39,4 +39,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h index 15e7a5a14f..b6102ae5ba 100644 --- a/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h +++ b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h index 22ca2ff7fd..d37098d45f 100644 --- a/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h +++ b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h index 665869a7b8..ff2322ea44 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h index d9ae367de6..8e66f4fac0 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h @@ -39,4 +39,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h index 198b7a9713..40e0163827 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h @@ -39,4 +39,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h index 7eb943670e..d905d5e67b 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h @@ -39,4 +39,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h index eea3c1dbc8..60e4295590 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h @@ -39,4 +39,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h index a980c4b6a7..0231ebc316 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h index fee58bf47a..0bd69a7d14 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h index 1bebc5bc97..f0fb2a5bdb 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h index 574f8d0c68..44f9f2ef51 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h index 21d00e801f..c51b1e03bd 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h index 68fbecc70b..33ebfcf49d 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h index e848072d29..38da666067 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h @@ -39,4 +39,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h index 7707257729..e9329ae0be 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h index b6fb86e80e..bb86bba8b1 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h @@ -39,4 +39,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h index 54410c9de0..d4f15c065e 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h index 252de11d4d..d57914c98b 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h index 68a690ea51..b21b79691c 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h index e324da47a0..ad9b98bf2d 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h index 749185de92..c6ca651157 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h index 65f80f4eea..f661f40340 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h index f38474b6d0..a1a2290f5e 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h index 2816d1bc7b..0bc1bf440d 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h @@ -39,4 +39,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h index 0c67adb4cb..fb9473cf12 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h @@ -38,4 +38,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h index f27b953dc6..a909de640b 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h @@ -46,4 +46,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h index 5fa7ea85db..3357ae1b51 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h index 532005cd1c..58c10a7486 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h index af430c0544..822969f9ed 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h index 4417a0d797..fa1b363b09 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h index 3ebf7c5818..d46069013c 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h index c26aa3df4a..a7a83c5d56 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h index e472803e7a..772c0cdbb8 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h index 8c2bcaadb2..af80fffe95 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h index 9386df16a8..f4cee56c83 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h @@ -39,4 +39,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h index e062b68540..b5c7aa1090 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h index 3b6fd77986..0ef674bcdb 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h index e48a280259..443f86788c 100644 --- a/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h +++ b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h @@ -39,4 +39,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h index b57016a1d0..1e7597be4b 100644 --- a/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h +++ b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h @@ -39,4 +39,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h index deccbce236..86b721fb5a 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h index 31bbbc5ea9..c135991192 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h index 9bba621e84..27c818be48 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h index 2d6e42f87a..a37ee5f510 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h @@ -39,4 +39,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h index ed4fe6dd2f..3e977b5260 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h index f9ae2b62c6..ae210445cc 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h @@ -39,4 +39,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h index a21b4353cc..b51cc10509 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h index 554c2d4d0c..d1f60cffbe 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h index 5fb23b1c84..d068d4448c 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h @@ -39,4 +39,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h index 55d1a67b3a..bb274f99da 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h index 87218cf548..35cc0f816a 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h @@ -39,4 +39,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h index 9e0250cd83..8a52a8e437 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h index da20315ff0..5e50a0f6ad 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h @@ -39,4 +39,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h index 934def91a2..6f50ef2b48 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h index 4b9dfb401c..a7d01131db 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h @@ -39,4 +39,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h index 495db0056e..8417d96303 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h index c2c9cea422..f84c4d339f 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h index 36ccdf32ca..cde77fa9e2 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h @@ -39,4 +39,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h index 234b7d47da..7c1fd4cc3d 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h @@ -39,4 +39,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h index bea4c81ac7..13564454bc 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h @@ -40,4 +40,4 @@ #pragma message(".h header is obsolete. Please use the .hpp") -#include \ No newline at end of file +#include From 31f6d4e45ea5233033bd9d1835f6d864ff62c907 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Fri, 22 Nov 2024 11:19:28 +0000 Subject: [PATCH 45/53] Fixes autogen script --- moveit/scripts/create_deprecated_headers.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/moveit/scripts/create_deprecated_headers.py b/moveit/scripts/create_deprecated_headers.py index 5f992c94bf..4ebc2bfa81 100755 --- a/moveit/scripts/create_deprecated_headers.py +++ b/moveit/scripts/create_deprecated_headers.py @@ -85,7 +85,7 @@ class DeprecatedHeader: def __init__(self, hpp: HppFile): self.hpp = hpp self.path = hpp.path.with_suffix(".h") - self.prefix = f"/* This file was autogenerated by {Path(__file__).name}" + self.prefix = f"/* This file was autogenerated by {Path(__file__).name} */" self.warn = '#pragma message(".h header is obsolete. Please use the .hpp")' self.contents = self.contents() @@ -126,4 +126,4 @@ def parse_args(args: List) -> bool: print(f"Proceeding to generate {len(processed)} .h files...") to_generate = [DeprecatedHeader(hpp) for hpp in processed] _ = [open(h.path, "w").write(h.contents) for h in to_generate] - print("Done.") + print("Done. (You may need to rerun formatting)") From 9793f4650fad96a31194f2a765bc9920c170ea03 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Sat, 23 Nov 2024 11:12:54 +0000 Subject: [PATCH 46/53] Delete moveit_core/macros/include/moveit/macros/deprecation.hpp --- .../include/moveit/macros/deprecation.hpp | 49 ------------------- 1 file changed, 49 deletions(-) delete mode 100644 moveit_core/macros/include/moveit/macros/deprecation.hpp diff --git a/moveit_core/macros/include/moveit/macros/deprecation.hpp b/moveit_core/macros/include/moveit/macros/deprecation.hpp deleted file mode 100644 index 2162988004..0000000000 --- a/moveit_core/macros/include/moveit/macros/deprecation.hpp +++ /dev/null @@ -1,49 +0,0 @@ -/********************************************************************* - * Software License Agreement (BSD License) - * - * Copyright (c) 2012, Willow Garage, Inc. - * 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 Willow Garage 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. - *********************************************************************/ - -#pragma once - -/** \def MOVEIT_DEPRECATED - Deprecated macro that marks functions as deprecated (TODO: Remove for Noetic) */ - -#warning "The usage of MOVEIT_DEPRECATED is deprecated. Use the CPP14 [[deprecated]] instead." -#ifdef __GNUC__ -#define MOVEIT_DEPRECATED __attribute__((deprecated)) -#elif defined(_MSC_VER) -#define MOVEIT_DEPRECATED __declspec(deprecated) -#elif defined(__clang__) -#define MOVEIT_DEPRECATED __attribute__((deprecated("MoveIt: Use of this method is deprecated"))) -#else -#define MOVEIT_DEPRECATED /* Nothing */ -#endif From 94032aa71451a049f0f7712e9da721457e28c892 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Sat, 23 Nov 2024 11:13:05 +0000 Subject: [PATCH 47/53] Delete moveit_core/macros/include/moveit/macros/deprecation.h --- .../include/moveit/macros/deprecation.h | 41 ------------------- 1 file changed, 41 deletions(-) delete mode 100644 moveit_core/macros/include/moveit/macros/deprecation.h diff --git a/moveit_core/macros/include/moveit/macros/deprecation.h b/moveit_core/macros/include/moveit/macros/deprecation.h deleted file mode 100644 index 378ee33607..0000000000 --- a/moveit_core/macros/include/moveit/macros/deprecation.h +++ /dev/null @@ -1,41 +0,0 @@ -/* This file was autogenerated by create_deprecated_headers.py */ - -/********************************************************************* - * Software License Agreement (BSD License) - * - * Copyright (c) 2012, Willow Garage, Inc. - * 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 Willow Garage 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. - *********************************************************************/ - -#pragma once - -#pragma message(".h header is obsolete. Please use the .hpp") - -#include From 23b3882d2d348d077a9be37c3d13b48c8b741f7a Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Tue, 26 Nov 2024 14:46:00 +0000 Subject: [PATCH 48/53] Update moveit/scripts/create_deprecated_headers.py Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> --- moveit/scripts/create_deprecated_headers.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/moveit/scripts/create_deprecated_headers.py b/moveit/scripts/create_deprecated_headers.py index 4ebc2bfa81..641cec09fb 100755 --- a/moveit/scripts/create_deprecated_headers.py +++ b/moveit/scripts/create_deprecated_headers.py @@ -45,7 +45,7 @@ def __init__(self, file: Path): class NoIncludeDirectory(Exception): - ERROR = "No includue directory found for {}.hpp. Unable to generate relative .hpp include" + ERROR = "No include directory found for {}.hpp. Unable to generate relative .hpp include" def __init__(self, file: Path): super().__init__(self.ERROR.format(file)) From e25d46aff368baf4272eae4197aca37c46180c95 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Tue, 26 Nov 2024 14:48:30 +0000 Subject: [PATCH 49/53] Update moveit/scripts/create_deprecated_headers.py Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> --- moveit/scripts/create_deprecated_headers.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/moveit/scripts/create_deprecated_headers.py b/moveit/scripts/create_deprecated_headers.py index 641cec09fb..7b38af4391 100755 --- a/moveit/scripts/create_deprecated_headers.py +++ b/moveit/scripts/create_deprecated_headers.py @@ -86,7 +86,7 @@ def __init__(self, hpp: HppFile): self.hpp = hpp self.path = hpp.path.with_suffix(".h") self.prefix = f"/* This file was autogenerated by {Path(__file__).name} */" - self.warn = '#pragma message(".h header is obsolete. Please use the .hpp")' + self.warn = '#pragma message(".h header is obsolete. Please use the .hpp header instead.")' self.contents = self.contents() def contents(self) -> str: From dda37c44025db267a76534ea2312bd18453c6093 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Tue, 26 Nov 2024 14:56:42 +0000 Subject: [PATCH 50/53] Updates script copyright --- moveit/scripts/create_deprecated_headers.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/moveit/scripts/create_deprecated_headers.py b/moveit/scripts/create_deprecated_headers.py index 7b38af4391..426c3a8504 100755 --- a/moveit/scripts/create_deprecated_headers.py +++ b/moveit/scripts/create_deprecated_headers.py @@ -1,7 +1,7 @@ #!/usr/bin/env python3 # -*- coding: utf-8 -*- -# Copyright 2021 PickNik Inc. +# Copyright 2024 Tom Noble. # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions are met: @@ -13,7 +13,7 @@ # notice, this list of conditions and the following disclaimer in the # documentation and/or other materials provided with the distribution. # -# * Neither the name of the PickNik Inc. nor the names of its +# * Neither the name of the copyright holder. nor the names of its # contributors may be used to endorse or promote products derived from # this software without specific prior written permission. # From 4e3667b2c92b1bd784242e75be91269275d76230 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Tue, 26 Nov 2024 19:19:35 +0000 Subject: [PATCH 51/53] Refactors script. Removes newline from parameter_name_list.hpp --- moveit/scripts/create_deprecated_headers.py | 83 +++++++++++++------ .../collision_detector_allocator_allvalid.h | 2 +- .../allvalid/collision_env_allvalid.h | 2 +- .../collision_detection/collision_common.h | 2 +- .../collision_detector_allocator.h | 2 +- .../collision_detection/collision_env.h | 2 +- .../collision_detection/collision_matrix.h | 2 +- .../collision_octomap_filter.h | 2 +- .../collision_detection/collision_plugin.h | 2 +- .../collision_plugin_cache.h | 2 +- .../collision_detection/collision_tools.h | 2 +- .../collision_detection/occupancy_map.h | 2 +- .../test_collision_common_panda.h | 2 +- .../test_collision_common_pr2.h | 2 +- .../moveit/collision_detection/world.h | 2 +- .../moveit/collision_detection/world_diff.h | 2 +- .../bullet_integration/basic_types.h | 2 +- .../bullet_integration/bullet_bvh_manager.h | 2 +- .../bullet_cast_bvh_manager.h | 2 +- .../bullet_discrete_bvh_manager.h | 2 +- .../bullet_integration/bullet_utils.h | 2 +- .../contact_checker_common.h | 2 +- .../bullet_integration/ros_bullet_utils.h | 2 +- .../collision_detector_allocator_bullet.h | 2 +- .../collision_detector_bullet_plugin_loader.h | 2 +- .../collision_env_bullet.h | 2 +- .../collision_common.h | 2 +- .../collision_detector_allocator_fcl.h | 2 +- .../collision_detector_fcl_plugin_loader.h | 2 +- .../collision_env_fcl.h | 2 +- .../collision_detection_fcl/fcl_compat.h | 2 +- .../collision_common_distance_field.h | 2 +- ...lision_detector_allocator_distance_field.h | 2 +- .../collision_detector_allocator_hybrid.h | 2 +- .../collision_distance_field_types.h | 2 +- .../collision_env_distance_field.h | 2 +- .../collision_env_hybrid.h | 2 +- .../constraint_samplers/constraint_sampler.h | 2 +- .../constraint_sampler_allocator.h | 2 +- .../constraint_sampler_manager.h | 2 +- .../constraint_sampler_tools.h | 2 +- .../default_constraint_samplers.h | 2 +- .../union_constraint_sampler.h | 2 +- .../controller_manager/controller_manager.h | 2 +- .../moveit/distance_field/distance_field.h | 2 +- .../distance_field/find_internal_points.h | 2 +- .../propagation_distance_field.h | 2 +- .../moveit/distance_field/voxel_grid.h | 2 +- .../moveit/dynamics_solver/dynamics_solver.h | 2 +- .../include/moveit/exceptions/exceptions.h | 2 +- .../kinematic_constraint.h | 2 +- .../moveit/kinematic_constraints/utils.h | 2 +- .../moveit/kinematics_base/kinematics_base.h | 2 +- .../kinematics_metrics/kinematics_metrics.h | 2 +- .../include/moveit/macros/class_forward.h | 2 +- .../include/moveit/macros/console_colors.h | 2 +- .../include/moveit/macros/declare_ptr.h | 2 +- .../acceleration_filter.h | 2 +- .../butterworth_filter.h | 2 +- .../online_signal_smoothing/ruckig_filter.h | 2 +- .../smoothing_base_class.h | 2 +- .../planning_interface/planning_interface.h | 2 +- .../planning_interface/planning_request.h | 2 +- .../planning_request_adapter.h | 2 +- .../planning_interface/planning_response.h | 2 +- .../planning_response_adapter.h | 2 +- .../moveit/planning_scene/planning_scene.h | 2 +- .../include/moveit/robot_model/aabb.h | 2 +- .../moveit/robot_model/fixed_joint_model.h | 2 +- .../moveit/robot_model/floating_joint_model.h | 2 +- .../include/moveit/robot_model/joint_model.h | 2 +- .../moveit/robot_model/joint_model_group.h | 2 +- .../include/moveit/robot_model/link_model.h | 2 +- .../moveit/robot_model/planar_joint_model.h | 2 +- .../robot_model/prismatic_joint_model.h | 2 +- .../moveit/robot_model/revolute_joint_model.h | 2 +- .../include/moveit/robot_model/robot_model.h | 2 +- .../moveit/robot_state/attached_body.h | 2 +- .../robot_state/cartesian_interpolator.h | 2 +- .../include/moveit/robot_state/conversions.h | 2 +- .../include/moveit/robot_state/robot_state.h | 2 +- .../robot_trajectory/robot_trajectory.h | 2 +- .../ruckig_traj_smoothing.h | 2 +- .../time_optimal_trajectory_generation.h | 2 +- .../time_parameterization.h | 2 +- .../trajectory_processing/trajectory_tools.h | 2 +- .../include/moveit/transforms/transforms.h | 2 +- .../include/moveit/utils/eigen_test_utils.h | 2 +- .../include/moveit/utils/lexical_casts.h | 2 +- .../utils/include/moveit/utils/logger.h | 2 +- .../include/moveit/utils/message_checks.h | 2 +- .../include/moveit/utils/moveit_error_code.h | 2 +- .../utils/include/moveit/utils/rclcpp_utils.h | 2 +- .../moveit/utils/robot_model_test_utils.h | 2 +- .../cached_ik_kinematics_plugin-inl.h | 2 +- .../cached_ik_kinematics_plugin.h | 2 +- .../detail/GreedyKCenters.h | 2 +- .../detail/NearestNeighbors.h | 2 +- .../detail/NearestNeighborsGNAT.h | 2 +- .../chainiksolver_vel_mimic_svd.h | 2 +- .../kdl_kinematics_plugin/joint_mimic.h | 2 +- .../kdl_kinematics_plugin.h | 2 +- .../srv_kinematics_plugin.h | 2 +- .../include/chomp_interface/chomp_interface.h | 2 +- .../chomp_interface/chomp_planning_context.h | 2 +- .../include/chomp_motion_planner/chomp_cost.h | 2 +- .../chomp_motion_planner/chomp_optimizer.h | 2 +- .../chomp_motion_planner/chomp_parameters.h | 2 +- .../chomp_motion_planner/chomp_planner.h | 2 +- .../chomp_motion_planner/chomp_trajectory.h | 2 +- .../chomp_motion_planner/chomp_utils.h | 2 +- .../multivariate_gaussian.h | 2 +- .../detail/constrained_goal_sampler.h | 2 +- .../detail/constrained_sampler.h | 2 +- .../detail/constraint_approximations.h | 2 +- .../detail/constraints_library.h | 2 +- .../moveit/ompl_interface/detail/goal_union.h | 2 +- .../ompl_interface/detail/ompl_constraints.h | 2 +- .../detail/projection_evaluators.h | 2 +- .../detail/state_validity_checker.h | 2 +- .../detail/threadsafe_state_storage.h | 2 +- .../model_based_planning_context.h | 2 +- .../moveit/ompl_interface/ompl_interface.h | 2 +- .../constrained_planning_state_space.h | 2 +- ...constrained_planning_state_space_factory.h | 2 +- .../joint_space/joint_model_state_space.h | 2 +- .../joint_model_state_space_factory.h | 2 +- .../model_based_state_space.h | 2 +- .../model_based_state_space_factory.h | 2 +- .../work_space/pose_model_state_space.h | 2 +- .../pose_model_state_space_factory.h | 2 +- .../ompl_interface/planning_context_manager.h | 2 +- .../include/joint_limits_copy/joint_limits.h | 2 +- .../joint_limits_copy/joint_limits_rosparam.h | 2 +- .../capability_names.h | 2 +- .../cartesian_trajectory.h | 2 +- .../cartesian_trajectory_point.h | 2 +- .../command_list_manager.h | 2 +- .../joint_limits_aggregator.h | 2 +- .../joint_limits_container.h | 2 +- .../joint_limits_extension.h | 2 +- .../joint_limits_interface_extension.h | 2 +- .../joint_limits_validator.h | 2 +- .../limits_container.h | 2 +- .../move_group_sequence_action.h | 2 +- .../move_group_sequence_service.h | 2 +- .../path_circle_generator.h | 2 +- .../pilz_industrial_motion_planner.h | 2 +- .../plan_components_builder.h | 2 +- .../planning_context_base.h | 2 +- .../planning_context_circ.h | 2 +- .../planning_context_lin.h | 2 +- .../planning_context_loader.h | 2 +- .../planning_context_loader_circ.h | 2 +- .../planning_context_loader_lin.h | 2 +- .../planning_context_loader_ptp.h | 2 +- .../planning_context_ptp.h | 2 +- .../planning_exceptions.h | 2 +- .../tip_frame_getter.h | 2 +- .../trajectory_blend_request.h | 2 +- .../trajectory_blend_response.h | 2 +- .../trajectory_blender.h | 2 +- .../trajectory_blender_transition_window.h | 2 +- .../trajectory_functions.h | 2 +- .../trajectory_generation_exceptions.h | 2 +- .../trajectory_generator.h | 2 +- .../trajectory_generator_circ.h | 2 +- .../trajectory_generator_lin.h | 2 +- .../trajectory_generator_ptp.h | 2 +- .../velocity_profile_atrap.h | 2 +- .../async_test.h | 2 +- .../basecmd.h | 2 +- .../cartesianconfiguration.h | 2 +- .../cartesianpathconstraintsbuilder.h | 2 +- .../center.h | 2 +- .../checks.h | 2 +- .../circ.h | 2 +- .../circ_auxiliary_types.h | 2 +- .../circauxiliary.h | 2 +- .../command_types_typedef.h | 2 +- .../default_values.h | 2 +- .../exception_types.h | 2 +- .../goalconstraintsmsgconvertible.h | 2 +- .../gripper.h | 2 +- .../interim.h | 2 +- .../jointconfiguration.h | 2 +- .../lin.h | 2 +- .../motioncmd.h | 2 +- .../motionplanrequestconvertible.h | 2 +- .../ptp.h | 2 +- .../robotconfiguration.h | 2 +- .../robotstatemsgconvertible.h | 2 +- .../sequence.h | 2 +- .../testdata_loader.h | 2 +- .../xml_constants.h | 2 +- .../xml_testdata_loader.h | 2 +- .../stomp_moveit/conversion_functions.h | 2 +- .../include/stomp_moveit/cost_functions.h | 2 +- .../include/stomp_moveit/filter_functions.h | 2 +- .../stomp_moveit/math/multivariate_gaussian.h | 2 +- .../include/stomp_moveit/noise_generators.h | 2 +- .../stomp_moveit_planning_context.h | 2 +- .../include/stomp_moveit/stomp_moveit_task.h | 2 +- .../stomp_moveit/trajectory_visualization.h | 2 +- .../ControllerHandle.h | 2 +- .../action_based_controller_handle.h | 2 +- .../empty_controller_handle.h | 2 +- ...ollow_joint_trajectory_controller_handle.h | 2 +- .../gripper_controller_handle.h | 2 +- .../moveit_py/moveit_py_utils/copy_ros_msg.h | 2 +- .../moveit_py_utils/ros_msg_typecasters.h | 2 +- .../moveit/benchmarks/BenchmarkExecutor.h | 2 +- .../moveit/benchmarks/BenchmarkOptions.h | 2 +- .../global_planner/global_planner_component.h | 2 +- .../global_planner/global_planner_interface.h | 2 +- .../global_planner/moveit_planning_pipeline.h | 2 +- .../hybrid_planning_events.h | 2 +- .../hybrid_planning_manager.h | 2 +- .../planner_logic_interface.h | 2 +- .../replan_invalidated_trajectory.h | 2 +- .../single_plan_execution.h | 2 +- .../forward_trajectory.h | 2 +- .../moveit/local_planner/feedback_types.h | 2 +- .../local_constraint_solver_interface.h | 2 +- .../local_planner/local_planner_component.h | 2 +- .../trajectory_operator_interface.h | 2 +- .../simple_sampler.h | 2 +- .../moveit/move_group/capability_names.h | 2 +- .../moveit/move_group/move_group_capability.h | 2 +- .../moveit/move_group/move_group_context.h | 2 +- .../include/moveit_servo/collision_monitor.h | 2 +- .../moveit_servo/include/moveit_servo/servo.h | 2 +- .../include/moveit_servo/servo_node.h | 2 +- .../include/moveit_servo/utils/command.h | 2 +- .../include/moveit_servo/utils/common.h | 2 +- .../include/moveit_servo/utils/datatypes.h | 2 +- .../occupancy_map_monitor.h | 2 +- .../occupancy_map_monitor_middleware_handle.h | 2 +- .../occupancy_map_updater.h | 2 +- .../depth_image_octomap_updater.h | 2 +- .../lazy_free_space_updater.h | 2 +- .../mesh_filter/depth_self_filter_nodelet.h | 2 +- .../include/moveit/mesh_filter/filter_job.h | 2 +- .../include/moveit/mesh_filter/gl_mesh.h | 2 +- .../include/moveit/mesh_filter/gl_renderer.h | 2 +- .../include/moveit/mesh_filter/mesh_filter.h | 2 +- .../moveit/mesh_filter/mesh_filter_base.h | 2 +- .../include/moveit/mesh_filter/sensor_model.h | 2 +- .../moveit/mesh_filter/stereo_camera_model.h | 2 +- .../moveit/mesh_filter/transform_provider.h | 2 +- .../point_containment_filter/shape_mask.h | 2 +- .../pointcloud_octomap_updater.h | 2 +- .../moveit/semantic_world/semantic_world.h | 2 +- .../collision_plugin_loader.h | 2 +- .../constraint_sampler_manager_loader.h | 2 +- .../kinematics_plugin_loader.h | 2 +- .../include/moveit/moveit_cpp/moveit_cpp.h | 2 +- .../moveit/moveit_cpp/planning_component.h | 2 +- .../moveit/plan_execution/plan_execution.h | 2 +- .../plan_execution/plan_representation.h | 2 +- .../planning_pipeline/planning_pipeline.h | 2 +- .../plan_responses_container.h | 2 +- .../planning_pipeline_interfaces.h | 2 +- .../solution_selection_functions.h | 2 +- .../stopping_criterion_functions.h | 2 +- .../current_state_monitor.h | 2 +- .../current_state_monitor_middleware_handle.h | 2 +- .../planning_scene_monitor.h | 2 +- .../trajectory_monitor.h | 2 +- .../trajectory_monitor_middleware_handle.h | 2 +- .../include/moveit/rdf_loader/rdf_loader.h | 2 +- .../synchronized_string_parameter.h | 2 +- .../robot_model_loader/robot_model_loader.h | 2 +- .../trajectory_execution_manager.h | 2 +- .../common_objects.h | 2 +- .../move_group_interface.h | 2 +- .../planning_scene_interface.h | 2 +- .../moveit/robot_interaction/interaction.h | 2 +- .../robot_interaction/interaction_handler.h | 2 +- .../interactive_marker_helpers.h | 2 +- .../robot_interaction/kinematic_options.h | 2 +- .../robot_interaction/kinematic_options_map.h | 2 +- .../robot_interaction/locked_robot_state.h | 2 +- .../robot_interaction/robot_interaction.h | 2 +- .../tests/include/parameter_name_list.h | 2 +- .../tests/include/parameter_name_list.hpp | 1 - .../trajectory_cache/trajectory_cache.h | 2 +- .../interactive_marker_display.h | 2 +- .../motion_planning_display.h | 2 +- .../motion_planning_frame.h | 2 +- .../motion_planning_frame_joints_widget.h | 2 +- .../motion_planning_param_widget.h | 2 +- .../background_processing.h | 2 +- .../planning_scene_display.h | 2 +- .../robot_state_display.h | 2 +- .../rviz_plugin_render_tools/octomap_render.h | 2 +- .../planning_link_updater.h | 2 +- .../planning_scene_render.h | 2 +- .../rviz_plugin_render_tools/render_shapes.h | 2 +- .../robot_state_visualization.h | 2 +- .../trajectory_panel.h | 2 +- .../trajectory_visualization.h | 2 +- .../include/ogre_helpers/mesh_shape.h | 2 +- .../trajectory_display.h | 2 +- .../moveit/warehouse/constraints_storage.h | 2 +- .../moveit/warehouse/moveit_message_storage.h | 2 +- .../moveit/warehouse/planning_scene_storage.h | 2 +- .../warehouse/planning_scene_world_storage.h | 2 +- .../include/moveit/warehouse/state_storage.h | 2 +- .../trajectory_constraints_storage.h | 2 +- .../moveit/warehouse/warehouse_connector.h | 2 +- .../moveit_setup_app_plugins/launch_bundle.h | 2 +- .../moveit_setup_app_plugins/launches.h | 2 +- .../launches_config.h | 2 +- .../launches_widget.h | 2 +- .../moveit_setup_app_plugins/perception.h | 2 +- .../perception_config.h | 2 +- .../perception_widget.h | 2 +- .../navigation_widget.h | 2 +- .../setup_assistant_widget.h | 2 +- .../control_xacro_config.h | 2 +- .../controller_edit_widget.h | 2 +- .../moveit_setup_controllers/controllers.h | 2 +- .../controllers_config.h | 2 +- .../controllers_widget.h | 2 +- .../included_xacro_config.h | 2 +- .../modified_urdf_config.h | 2 +- .../moveit_controllers.h | 2 +- .../moveit_controllers_config.h | 2 +- .../ros2_controllers.h | 2 +- .../ros2_controllers_config.h | 2 +- .../urdf_modifications.h | 2 +- .../urdf_modifications_widget.h | 2 +- .../author_information.h | 2 +- .../author_information_widget.h | 2 +- .../configuration_files.h | 2 +- .../configuration_files_widget.h | 2 +- .../moveit_setup_core_plugins/start_screen.h | 2 +- .../start_screen_widget.h | 2 +- .../include/moveit_setup_framework/config.h | 2 +- .../data/package_settings_config.h | 2 +- .../moveit_setup_framework/data/srdf_config.h | 2 +- .../moveit_setup_framework/data/urdf_config.h | 2 +- .../moveit_setup_framework/data_warehouse.h | 2 +- .../moveit_setup_framework/generated_file.h | 2 +- .../moveit_setup_framework/generated_time.h | 2 +- .../qt/double_list_widget.h | 2 +- .../qt/helper_widgets.h | 2 +- .../moveit_setup_framework/qt/rviz_panel.h | 2 +- .../qt/setup_step_widget.h | 2 +- .../qt/xml_syntax_highlighter.h | 2 +- .../moveit_setup_framework/setup_step.h | 2 +- .../moveit_setup_framework/templates.h | 2 +- .../moveit_setup_framework/testing_utils.h | 2 +- .../moveit_setup_framework/utilities.h | 2 +- .../moveit_setup_simulation/simulation.h | 2 +- .../simulation_widget.h | 2 +- .../collision_linear_model.h | 2 +- .../collision_matrix_model.h | 2 +- .../compute_default_collisions.h | 2 +- .../default_collisions.h | 2 +- .../default_collisions_widget.h | 2 +- .../moveit_setup_srdf_plugins/end_effectors.h | 2 +- .../end_effectors_widget.h | 2 +- .../group_edit_widget.h | 2 +- .../group_meta_config.h | 2 +- .../kinematic_chain_widget.h | 2 +- .../passive_joints.h | 2 +- .../passive_joints_widget.h | 2 +- .../planning_groups.h | 2 +- .../planning_groups_widget.h | 2 +- .../moveit_setup_srdf_plugins/robot_poses.h | 2 +- .../robot_poses_widget.h | 2 +- .../rotated_header_view.h | 2 +- .../moveit_setup_srdf_plugins/srdf_step.h | 2 +- .../virtual_joints.h | 2 +- .../virtual_joints_widget.h | 2 +- 377 files changed, 432 insertions(+), 402 deletions(-) diff --git a/moveit/scripts/create_deprecated_headers.py b/moveit/scripts/create_deprecated_headers.py index 426c3a8504..73bf78135f 100755 --- a/moveit/scripts/create_deprecated_headers.py +++ b/moveit/scripts/create_deprecated_headers.py @@ -13,7 +13,7 @@ # notice, this list of conditions and the following disclaimer in the # documentation and/or other materials provided with the distribution. # -# * Neither the name of the copyright holder. nor the names of its +# * Neither the name of the copyright holder nor the names of its # contributors may be used to endorse or promote products derived from # this software without specific prior written permission. # @@ -32,6 +32,7 @@ # Author: Tom Noble import sys +import argparse import logging from typing import List, Tuple from pathlib import Path @@ -91,7 +92,7 @@ def __init__(self, hpp: HppFile): def contents(self) -> str: items = [self.prefix, self.hpp.pretext, self.warn, self.hpp.include] - return "\n\n".join(items) + return "\n\n".join(items) + "\n" def parse_args(args: List) -> bool: @@ -102,28 +103,58 @@ def parse_args(args: List) -> bool: return apply -if __name__ == "__main__": - apply = parse_args(sys.argv) - hpp_paths = list(Path.cwd().rglob("*.hpp")) - print(f"Generating deprecated .h files for {len(hpp_paths)} .hpp files...") - processed = [] - bad = [] - for hpp_path in hpp_paths: +class HeaderSummary: + def __init__(self, n_processed_hpps: int, bad_hpps: List[str]): + self.n_processed_hpps = n_processed_hpps + self.bad_hpps = bad_hpps + + def were_all_hpps_processed(self) -> bool: + return len(self.bad_hpps) == 0 + + def __repr__(self) -> str: + summary = f"Can generate {self.n_processed_hpps} .h files." + if self.bad_hpps: + summary += f" Cannot generate {len(self.bad_hpps)} .h files:\n\n" + summary += "\n".join([f"❌ {hpp}" for hpp in self.bad_hpps]) + summary += "\n" + return summary + + +class DeprecatedHeaderGenerator: + def __init__(self, hpp_paths: List[str]): + self.hpp_paths = hpp_paths + self.processed_hpps = [] + self.bad_hpps = [] + + def __process_hpp(self, hpp: str) -> None: try: - processed.append(HppFile(hpp_path)) - except NoIncludeDirectory as e: - bad.append(str(hpp_path)) - except NoIncludeGuard as e: - bad.append(str(hpp_path)) - print(f"Summary: Can generate {len(processed)} .h files") - if bad: - print(f"Cannot generate .h files for the following files:") - print("\n".join(bad)) - if apply and bad: - answer = input("Proceed to generate? (y/n): ") - apply = answer.lower() == "y" - if apply: - print(f"Proceeding to generate {len(processed)} .h files...") - to_generate = [DeprecatedHeader(hpp) for hpp in processed] - _ = [open(h.path, "w").write(h.contents) for h in to_generate] - print("Done. (You may need to rerun formatting)") + self.processed_hpps.append(HppFile(hpp)) + except (NoIncludeDirectory, NoIncludeGuard) as e: + self.bad_hpps.append(str(hpp)) + + def process_all_hpps(self) -> HeaderSummary: + print(f"\nProcessing {len(self.hpp_paths)} .hpp files...") + _ = [self.__process_hpp(hpp) for hpp in self.hpp_paths] + return HeaderSummary(len(self.processed_hpps), self.bad_hpps) + + def create_h_files(self) -> None: + print(f"Proceeding to generate {len(self.processed_hpps)} .h files...") + h_files = [DeprecatedHeader(hpp) for hpp in self.processed_hpps] + _ = [open(h.path, "w").write(h.contents) for h in h_files] + + +if __name__ == "__main__": + parser = argparse.ArgumentParser() + # TODO: Add argument for skipping private headers + parser.add_argument("--apply", action="store_true", help="Generates the .h files") + args = parser.parse_args() + generator = DeprecatedHeaderGenerator(list(Path.cwd().rglob("*.hpp"))) + summary = generator.process_all_hpps() + print(summary) + if args.apply and not summary.were_all_hpps_processed(): + args.apply = input("Continue? (y/n): ").lower() == "y" + if args.apply: + generator.create_h_files() + else: + print("Skipping file generation...") + print("Done.\n") diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h index 2cc400ec92..f14ae1d94a 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h index 869861d7a9..f6830cbd71 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h index 9ceb56b066..980f98d533 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h index c28acf0993..c49049bfed 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h index 529c8cefc4..38f40738ea 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h index cd1a720d32..0aa197d3e9 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h index 5b86596d41..7485d9dd55 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h index 6833d7c26a..d33d122484 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h index fc446ddcbf..be1c89f288 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h index 4fa1eb74fe..2d6f697f1f 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h b/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h index 8c0c8ada8b..ebab3a1ac1 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h index 496df6ceee..6cebcf0835 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h index 9e9c787de8..0fb9ce2d5c 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/world.h b/moveit_core/collision_detection/include/moveit/collision_detection/world.h index 9c5d42560d..af62d7c0bb 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/world.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/world.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h b/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h index 23b2eb1716..29ede92cef 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h index f62361dba0..19f78b8fa8 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h @@ -22,6 +22,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h index e05390b07f..c09ba17b69 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h @@ -35,6 +35,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h index 8c127c4e2a..3ce5440a28 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h @@ -35,6 +35,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h index ff7c5b9784..42862e24f3 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h @@ -35,6 +35,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h index 1a65f42407..e1f47c2976 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h index 117e76edb0..b3dce862fa 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h @@ -22,6 +22,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h index c0ed859038..cf8417138c 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h @@ -22,6 +22,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h index b11de1d5d8..f14d95f68f 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h index 884361bce3..849a7652d6 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h index 86c03d067d..34ef2d49a3 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h index b37ad61329..94c4735ba5 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h index 4d14c990e3..0a10b9230e 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h index 65a42060cd..d0634926df 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h index cdf1ac8f7b..cef67046a4 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h index 6a0e33c5a8..7c0a490f34 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h index b3c60923ff..6c0db44b20 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h index 56dab33c44..5043a88023 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h index 9e2ceb047d..c46919a022 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h index a0eb0b5bc5..c87441bc65 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h index 14262748c0..777e771d6c 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h index 33d61d0095..79c5675b42 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h index 74b8c2f5c1..31aa8ddd3e 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h index 361301a2c7..96854a1c27 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h index a2967ad216..b797e85bc6 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h index 941149b085..08048df931 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h index 2d827d79a1..4b14a14757 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h index eb66c58e1f..40cfb1dbd4 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h b/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h index d755079e4d..9db4f0ae64 100644 --- a/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h +++ b/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/distance_field/include/moveit/distance_field/distance_field.h b/moveit_core/distance_field/include/moveit/distance_field/distance_field.h index 175aa0660e..e2cb9761f0 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/distance_field.h +++ b/moveit_core/distance_field/include/moveit/distance_field/distance_field.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h b/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h index 5d78049852..f17e8a6945 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h +++ b/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h b/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h index 467304bcff..81b2140609 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h +++ b/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h b/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h index 5cb57e8b5e..fd976c521b 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h +++ b/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h b/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h index bc029f70a1..59728aea0f 100644 --- a/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h +++ b/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/exceptions/include/moveit/exceptions/exceptions.h b/moveit_core/exceptions/include/moveit/exceptions/exceptions.h index f5255844d5..5eaaa848ee 100644 --- a/moveit_core/exceptions/include/moveit/exceptions/exceptions.h +++ b/moveit_core/exceptions/include/moveit/exceptions/exceptions.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h index da3c805561..3aa43f5718 100644 --- a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h +++ b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h index 9d53853999..e2c614c55f 100644 --- a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h +++ b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h index 0b9e9b5c18..0b2181de44 100644 --- a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h +++ b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h b/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h index c0bfdcb5a4..0c0320e89a 100644 --- a/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h +++ b/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/macros/include/moveit/macros/class_forward.h b/moveit_core/macros/include/moveit/macros/class_forward.h index 0672af5f0e..654be06053 100644 --- a/moveit_core/macros/include/moveit/macros/class_forward.h +++ b/moveit_core/macros/include/moveit/macros/class_forward.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/macros/include/moveit/macros/console_colors.h b/moveit_core/macros/include/moveit/macros/console_colors.h index d3caa6fa54..ae7dbe9573 100644 --- a/moveit_core/macros/include/moveit/macros/console_colors.h +++ b/moveit_core/macros/include/moveit/macros/console_colors.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/macros/include/moveit/macros/declare_ptr.h b/moveit_core/macros/include/moveit/macros/declare_ptr.h index 95c4553e8d..43e25e3c68 100644 --- a/moveit_core/macros/include/moveit/macros/declare_ptr.h +++ b/moveit_core/macros/include/moveit/macros/declare_ptr.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h index c0fa16deb0..ff0c599ca0 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h @@ -74,6 +74,6 @@ c --------x--- v | #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h index 283e3c73dd..34275f41f1 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h index 191dd9ac6a..59e624ac31 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h @@ -40,6 +40,6 @@ Description: Applies jerk/acceleration/velocity limits to online motion commands #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h index 76312e06f1..68e030d9c7 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h @@ -40,6 +40,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h index 1ec25f02c5..df37b805ea 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h index f7f1fb90e1..9f59f37bc6 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h index c4d213da6e..fa8feb9643 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h @@ -40,6 +40,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h index 3719729058..6459650554 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h index a5aef5018d..24bc88140e 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h index 971c48b105..f8ee76c3f4 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/aabb.h b/moveit_core/robot_model/include/moveit/robot_model/aabb.h index a0a27d69bc..e3223af591 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/aabb.h +++ b/moveit_core/robot_model/include/moveit/robot_model/aabb.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h index 0f75393809..91f937e907 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h index 8bbfdc48e4..2986947ea8 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/joint_model.h index 068b57b256..ac0f3e5404 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/joint_model.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h index d8ee3e7d7f..6271c6de66 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h +++ b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/link_model.h b/moveit_core/robot_model/include/moveit/robot_model/link_model.h index b51bfdea1f..16ffcae4ed 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/link_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/link_model.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h index 3012f330b5..4a7c6d45b6 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h index 26a33af320..e7b8d69a85 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h index 2298b04313..3de10f22c3 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h index f3b542586f..22436148e8 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/robot_state/include/moveit/robot_state/attached_body.h b/moveit_core/robot_state/include/moveit/robot_state/attached_body.h index 5f5da7f9bc..b2491acd54 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/attached_body.h +++ b/moveit_core/robot_state/include/moveit/robot_state/attached_body.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h b/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h index 70c2b68fb7..44f699f6c6 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h +++ b/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h @@ -40,6 +40,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/robot_state/include/moveit/robot_state/conversions.h b/moveit_core/robot_state/include/moveit/robot_state/conversions.h index 9ac01e17ea..98cc197734 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/conversions.h +++ b/moveit_core/robot_state/include/moveit/robot_state/conversions.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h index 64fcd4ad52..7d52ff1e42 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h +++ b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h index a1be2291e0..0dba39fc91 100644 --- a/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h +++ b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h index a56508c0c2..b170a8c0f7 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h @@ -37,6 +37,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h index a1763bb4c0..a696e49a06 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h @@ -40,6 +40,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h index 4d6163c289..4a38effafb 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h @@ -2,6 +2,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h index 1ad1d58c74..357ec23b0f 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/transforms/include/moveit/transforms/transforms.h b/moveit_core/transforms/include/moveit/transforms/transforms.h index 21f6f7152e..6bb5724953 100644 --- a/moveit_core/transforms/include/moveit/transforms/transforms.h +++ b/moveit_core/transforms/include/moveit/transforms/transforms.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/utils/include/moveit/utils/eigen_test_utils.h b/moveit_core/utils/include/moveit/utils/eigen_test_utils.h index 502de6298b..0bb942c5db 100644 --- a/moveit_core/utils/include/moveit/utils/eigen_test_utils.h +++ b/moveit_core/utils/include/moveit/utils/eigen_test_utils.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/utils/include/moveit/utils/lexical_casts.h b/moveit_core/utils/include/moveit/utils/lexical_casts.h index df163601bd..110051fec4 100644 --- a/moveit_core/utils/include/moveit/utils/lexical_casts.h +++ b/moveit_core/utils/include/moveit/utils/lexical_casts.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/utils/include/moveit/utils/logger.h b/moveit_core/utils/include/moveit/utils/logger.h index 19afba16aa..10ce652921 100644 --- a/moveit_core/utils/include/moveit/utils/logger.h +++ b/moveit_core/utils/include/moveit/utils/logger.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/utils/include/moveit/utils/message_checks.h b/moveit_core/utils/include/moveit/utils/message_checks.h index 4acd7a0b76..dfbb2f8614 100644 --- a/moveit_core/utils/include/moveit/utils/message_checks.h +++ b/moveit_core/utils/include/moveit/utils/message_checks.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/utils/include/moveit/utils/moveit_error_code.h b/moveit_core/utils/include/moveit/utils/moveit_error_code.h index c581490398..a18743f139 100644 --- a/moveit_core/utils/include/moveit/utils/moveit_error_code.h +++ b/moveit_core/utils/include/moveit/utils/moveit_error_code.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/utils/include/moveit/utils/rclcpp_utils.h b/moveit_core/utils/include/moveit/utils/rclcpp_utils.h index 50b40c0578..f17e8ea8ef 100644 --- a/moveit_core/utils/include/moveit/utils/rclcpp_utils.h +++ b/moveit_core/utils/include/moveit/utils/rclcpp_utils.h @@ -29,6 +29,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h b/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h index d158b356b6..43b9fbd50e 100644 --- a/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h +++ b/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h index 487fa7b11a..ff35846101 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h index 334e836730..b0106ce66c 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h index 32969443b4..0ef8eb1c36 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h @@ -40,6 +40,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h index 63ca8d785f..406f3035e2 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h @@ -40,6 +40,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h index 04a8bf2338..e1b6d45f64 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h @@ -40,6 +40,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h index 0b0eadcc2d..919a770bad 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h +++ b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h @@ -27,6 +27,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h index 12d8d6b63b..0dea3f60f9 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h +++ b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h index cef3bac3a3..ee0c94edf4 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h +++ b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h b/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h index fb254f56d9..c920152168 100644 --- a/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h +++ b/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h @@ -43,6 +43,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h index 49801844d3..11a21a4f5b 100644 --- a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h +++ b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h index 5f3549706d..1e0544b0f2 100644 --- a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h +++ b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h index a94ebd67b9..a69ff94bc6 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h index 5db2c5fffa..f358e2f3f5 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h index 838652f3fa..c1f4d0969c 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h index 9bea627d9a..6f9b71283e 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h index 9f40c14523..b065aecaf9 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h index fb7100ec1c..499a90b227 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h index 68b8e8c4a3..7354558ac7 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h index 4a8a19ef13..aabfe63422 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h index 76b2b41cbc..b04f23d551 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h index ed41697b8d..b3c0bc9ebe 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h index 8e95035359..4d65cfe9c3 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h index 20c672ba95..bb5fc103b0 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h index f7f297c63b..8f5c851170 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h index f397b1db06..69b7187c9e 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h index 2ab0209014..24e54c0a17 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h @@ -49,6 +49,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h index ae49ac9319..4f700ff6a3 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h index 86320a9b48..b032e745fe 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h index 333eabd246..25c628318a 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h index beaad450d0..fea175ca70 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h index 9b4fce28e8..81ec299d95 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h index ab411e16cf..1129ba99d4 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h index 1c6177a1a6..ad61bcffb3 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h index 08b72799a7..ce116bfb9f 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h index 57c5e71527..ac9319f476 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h index ae5d49300e..2778536547 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h index 9ac5e8f08f..f7679a896e 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h index 1b08d92ffa..31d23e9507 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h index 86aa0b2489..854aa32805 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h @@ -18,6 +18,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h index 0b01801bd8..18d39bed10 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h @@ -18,6 +18,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h index 623cf5d388..d6655eb8b3 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h index cf993e9597..c2778f2cc8 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h index 27148547b2..5754337126 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h index 2119cf8d4f..6bf6136259 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h index f897cdcb9f..39a36e1223 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h index be11f04abe..0419683d73 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h index 90cf4c05bc..cfaf5c78c4 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h index 334c6b8541..813357bc67 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h index 1a7b2cc4cf..eefa8cecd1 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h index f7313c7da6..5c8160a2b8 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h index 9e2636131e..5676de3c2a 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h index 7b1030ff55..60b67d2643 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h index 39c43daea0..98f3b8ba2b 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h index cdf2e089f9..59994f0a3f 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h index 2d3c856904..f3df93cb35 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h index d25357116b..9dab16b5c4 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h index cf489f1ad2..5f55bacd4d 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h index 7e6fb14cc2..a19e8d39f5 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h index 5561b7e96c..ab9de2d1c0 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h index 550f50ab96..f423e48787 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h index 5474966315..6b23d4f073 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h index eb03da07e6..590f3f687a 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h index d01c4464ca..690eed96dc 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h index f1c7882c70..42e96c0006 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h index a9f036615a..05a40515d8 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h index 67f84dc688..6e65d4c823 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h index 132b6dbbf8..1bbc0cf177 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h index 7ebf68b68a..ac8c479466 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h index deffe14550..5b98e893b1 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h index 520984cf13..d4d530001c 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h index b89d6952db..4d0d963fd4 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h index 80ec42dd58..ce2d27417f 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h index 3dab1fe486..1eb091e23c 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h index 95316e909f..28bb31be2b 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h index 4f62103dfe..3df3259582 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h index 01624f4946..23bbc1218e 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h index bd2e6a6013..b20ecd3407 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h @@ -18,6 +18,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h index d263360e51..60943b75be 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h index 561dfa0848..9f090df6fd 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h index c32220b13b..f293dfd801 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h index 5ffd3fcd48..d1a63e40fd 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h index 806e89d721..61dec12e0e 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h index a05fc27433..be0de6232a 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h index 12d68b9af0..7740480e42 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h index 5546efbfec..136e29b05c 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h index 61bb944fc1..bcb07fbc4e 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h index 2c8a36a27f..67868fafa6 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h index 4edd1d6368..982da25593 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h index 16105a1888..7d73eeab35 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h index ed40838e5c..4c916dc200 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h index 05710f0786..a632cc5648 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h index 981dbb66ef..b7bb752db5 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h index 1b82054e20..cb2a80f896 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h index 76b9eabbed..d55835ab43 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h index ba09ebc5df..f64f71b75d 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h index 7cbb25b11b..419eb886e9 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h index d0e6cc7951..dbf085b973 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h index 2a6420b046..ed3e186fc4 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h index dbfc6831c3..6ea7364a94 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h index 03eaef20bf..df1a082dfb 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h index 4ac7e23e8d..b84c542579 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h index ab693267e7..9517b28f32 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h b/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h index c4353b19ad..60bdfd5bda 100644 --- a/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h +++ b/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/stomp/include/stomp_moveit/cost_functions.h b/moveit_planners/stomp/include/stomp_moveit/cost_functions.h index 26d5bb757a..13c98008f5 100644 --- a/moveit_planners/stomp/include/stomp_moveit/cost_functions.h +++ b/moveit_planners/stomp/include/stomp_moveit/cost_functions.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/stomp/include/stomp_moveit/filter_functions.h b/moveit_planners/stomp/include/stomp_moveit/filter_functions.h index 8afe0d34f9..9968470c5c 100644 --- a/moveit_planners/stomp/include/stomp_moveit/filter_functions.h +++ b/moveit_planners/stomp/include/stomp_moveit/filter_functions.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h b/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h index e94f9a9445..68edd4c4e8 100644 --- a/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h +++ b/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/stomp/include/stomp_moveit/noise_generators.h b/moveit_planners/stomp/include/stomp_moveit/noise_generators.h index e84a3217d0..1b7c12ddf0 100644 --- a/moveit_planners/stomp/include/stomp_moveit/noise_generators.h +++ b/moveit_planners/stomp/include/stomp_moveit/noise_generators.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h index 3e217e6ec2..5e59826ffc 100644 --- a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h +++ b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h index 3dc922cdcb..b62661212c 100644 --- a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h +++ b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h @@ -56,6 +56,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h b/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h index 182a568121..766883eda3 100644 --- a/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h +++ b/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h b/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h index 72b32af6f0..77ca596ddc 100644 --- a/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h +++ b/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h index f7d654a8f5..f1886c97dc 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h index dbff9094ac..556616144d 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h index 4d25d743ec..e4ed2fddf8 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h index 960ca9f9b5..d86f8dd8a3 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h index f215dc1201..2ffa98fbe9 100644 --- a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h +++ b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h index 7696f68a70..dec636ff47 100644 --- a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h +++ b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h index 0dcd0aaf0e..302be23035 100644 --- a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h +++ b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h index 07ba256b94..58d9784dff 100644 --- a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h +++ b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h index d73b113f41..562a060ebb 100644 --- a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h +++ b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h @@ -40,6 +40,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h index 796c340767..4bcb507cc9 100644 --- a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h +++ b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h b/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h index ece0b29165..a707923b29 100644 --- a/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h +++ b/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h index bd171df69c..4f1c64b02a 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h @@ -39,6 +39,6 @@ */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h index 4e86535a5c..a43c8ac6e4 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h @@ -40,6 +40,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h index 45183839ce..ea0876ac24 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h @@ -40,6 +40,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h index 82caf35cec..29d651e91b 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h @@ -42,6 +42,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h index ce07623ad8..001139a0ee 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h b/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h index 3700846a34..c8e38dd928 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h +++ b/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h @@ -42,6 +42,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h index 53dc4f1fa2..86d70f3a2b 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h index a292f6163a..423f9cc6a3 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h @@ -40,6 +40,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h index 230c1cd5db..1f7b534158 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h index 6331ed1930..4100683b60 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h @@ -40,6 +40,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h b/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h index d6594245cc..45be7faa22 100644 --- a/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h +++ b/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h @@ -42,6 +42,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/move_group/include/moveit/move_group/capability_names.h b/moveit_ros/move_group/include/moveit/move_group/capability_names.h index efa01718d0..db6a192c61 100644 --- a/moveit_ros/move_group/include/moveit/move_group/capability_names.h +++ b/moveit_ros/move_group/include/moveit/move_group/capability_names.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h b/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h index 309771bed6..9c6438ba52 100644 --- a/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h +++ b/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/move_group/include/moveit/move_group/move_group_context.h b/moveit_ros/move_group/include/moveit/move_group/move_group_context.h index 8a815d0803..7d938687fb 100644 --- a/moveit_ros/move_group/include/moveit/move_group/move_group_context.h +++ b/moveit_ros/move_group/include/moveit/move_group/move_group_context.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h b/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h index 39ee60647a..ac61f35e65 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h @@ -43,6 +43,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/servo.h b/moveit_ros/moveit_servo/include/moveit_servo/servo.h index 5c2775a6c9..23d9786d3f 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/servo.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/servo.h @@ -43,6 +43,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h b/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h index ed0613b831..e85910edf3 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h @@ -43,6 +43,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h b/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h index 1be5adb12d..aecb55585a 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h @@ -43,6 +43,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h b/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h index 1d71f5f93d..d5d3d8d283 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h @@ -43,6 +43,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h b/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h index 077a08857f..51311c7bf2 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h @@ -43,6 +43,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h index 15ce4d9157..2cfa100a12 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h index 590414dff2..3749b19609 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h index 08d76f4d40..cf5166a878 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h b/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h index ad3200955d..fd53b22f0e 100644 --- a/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h +++ b/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h b/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h index 793ebdb82a..ae545cb8d7 100644 --- a/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h +++ b/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h index 6773febabb..7183540b5b 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h index 81bad2aba0..fdb3a5e89f 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h index 10da7fc760..b580d22b12 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h index ae243007d3..0221343703 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h index 0a6467dad1..5e741b17a0 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h index 38e5235d5f..16e874fb64 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h index d20606a7f5..d8cfb0ff3d 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h index 94b9921780..7b05f58e0e 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h index 5a5a5b7542..be0d457f7d 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h b/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h index b932008ffc..e053a75a7f 100644 --- a/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h +++ b/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h b/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h index 4867721c0a..65a1835a33 100644 --- a/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h +++ b/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h index f70bae33d6..606d919539 100644 --- a/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h +++ b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h b/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h index 333778f9ad..b53a58d9bb 100644 --- a/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h +++ b/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h b/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h index f3d080bf1a..501aca2da3 100644 --- a/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h +++ b/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h b/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h index 02dca8cabb..4fac35d82f 100644 --- a/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h +++ b/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h index 4f9e19dc48..ef53158a73 100644 --- a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h +++ b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h index 3f90593721..f396eebbc4 100644 --- a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h +++ b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h index 4aab5668c1..9073883eef 100644 --- a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h +++ b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h index 18119f94c1..3457baa5c6 100644 --- a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h +++ b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h index 8879080882..2cb45c37be 100644 --- a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h +++ b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h @@ -41,6 +41,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h index de4e9f719e..bf82ed1cb5 100644 --- a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h index c01195ca4e..8353e03903 100644 --- a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h index 35ce8911e0..e693f2c5c7 100644 --- a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h index d372a72e04..215278477d 100644 --- a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h index 79beb2562f..65e6b263e4 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h index 80ecf0d023..2e60ee0abe 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h index 93baee4489..ef159ee184 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h index 1cd008cbac..3b2972a7bd 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h index 91c9711f52..72c5fa55d2 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h index 4640cfbf8c..a3e6123240 100644 --- a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h +++ b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h index 98b4e0052d..16e25fa3e7 100644 --- a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h +++ b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h b/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h index ca4b221d14..d577717cee 100644 --- a/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h +++ b/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h index 770bc32b92..58c3d5dafd 100644 --- a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h +++ b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h b/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h index 70fce5a27e..6ae3c57b89 100644 --- a/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h +++ b/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h index f618e290ba..e5ff7a88e6 100644 --- a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h +++ b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h b/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h index 425f85dc32..52538c7f76 100644 --- a/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h +++ b/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h index 26cf97bf31..1578dfd801 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h index 179c0a9e1c..54293cdf34 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h index cd626080cb..bb71588cdb 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h index 7900d8afed..86c1961545 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h index eb2a9ac367..23419669e5 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h index d879bd8b24..dfb2304ad0 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h @@ -39,6 +39,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h index 2acb62a7e6..6080c51212 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/tests/include/parameter_name_list.h b/moveit_ros/tests/include/parameter_name_list.h index d7cc404d13..d8929212e7 100644 --- a/moveit_ros/tests/include/parameter_name_list.h +++ b/moveit_ros/tests/include/parameter_name_list.h @@ -40,6 +40,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/tests/include/parameter_name_list.hpp b/moveit_ros/tests/include/parameter_name_list.hpp index 913a482b62..8505c48e3f 100644 --- a/moveit_ros/tests/include/parameter_name_list.hpp +++ b/moveit_ros/tests/include/parameter_name_list.hpp @@ -1,4 +1,3 @@ - /********************************************************************* * Software License Agreement (BSD License) * diff --git a/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h b/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h index d049693521..a124a872c6 100644 --- a/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h +++ b/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h @@ -21,6 +21,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h index b20d10517d..475afbae12 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h @@ -37,6 +37,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h index fb92f6098f..8f198f29b6 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h index 006cc0c842..ac0b2d95cf 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h index 3ad72683f2..ea14effb61 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h index b5854d836f..5a703a100a 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h index 65cdc806d5..23680adc3e 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h index d9572c06ad..103734df79 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h b/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h index f7b7b0179d..5e35f9445c 100644 --- a/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h +++ b/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h index 1129ce07a2..7c3fa4097a 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h index d1eae788e3..2a9e44693f 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h index dea106ee87..b7a5019631 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h index 03605fe053..de5f953701 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h index 6959add96d..dc9e390318 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h index c9f41a8e49..83d50889a2 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h index d1e5943aa6..a4ca6a4263 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h index 2f33de77b8..889cc3356e 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h @@ -31,6 +31,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h b/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h index 052ec279d4..1d830fa91b 100644 --- a/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h +++ b/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h @@ -40,6 +40,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h index 6d340a3893..d7689aebab 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h index 4d7c3237af..2728c0ab3b 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h index ab7d4ddb73..2ad6b1a06b 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h index 029914de5e..be125d940a 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h index 64fe81fac3..617c8ceffb 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h index 9ab4a54d4a..b23f8c7fcf 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h b/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h index be72e8fea0..cad7b15679 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h index 300da2d8b1..3caac03ac5 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h index 6932f018fe..ee377cc1c9 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h index 1281141665..34f19804f3 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h index 3381af5951..2b9c64768f 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h index b9e2282fc3..09ed271e2e 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h index ef4007385c..ca38ed7319 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h index c4a0f45dec..3b3470e592 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h @@ -37,6 +37,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h index b6102ae5ba..7fbdef4413 100644 --- a/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h +++ b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h index d37098d45f..807f0e9f59 100644 --- a/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h +++ b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h index ff2322ea44..4eeacbfe8f 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h index 8e66f4fac0..7e55cd1130 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h @@ -37,6 +37,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h index 40e0163827..ed45a866e7 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h index d905d5e67b..72647016df 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h index 60e4295590..2f9f76cf84 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h @@ -37,6 +37,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h index 0231ebc316..dbb5f0f5f8 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h index 0bd69a7d14..1a99f34c73 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h index f0fb2a5bdb..41d6f6c8ce 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h index 44f9f2ef51..47ff73d8c6 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h index c51b1e03bd..777eb911b7 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h index 33ebfcf49d..d2a1c98d24 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h index 38da666067..b546c74d3d 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h index e9329ae0be..fa6131d830 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h index bb86bba8b1..bac4ccfee5 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h index d4f15c065e..ee833937a0 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h index d57914c98b..5634d29417 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h index b21b79691c..26591afdec 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h index ad9b98bf2d..2136002c7f 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h index c6ca651157..9f59ce62c4 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h index f661f40340..ff8c62dadf 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h index a1a2290f5e..f2b9de8a46 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h index 0bc1bf440d..05120e5e5e 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h index fb9473cf12..37ad336a46 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h @@ -36,6 +36,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h index a909de640b..521a80ea5f 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h @@ -44,6 +44,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h index 3357ae1b51..bd365a2e46 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h index 58c10a7486..07151ceffd 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h index 822969f9ed..fe87ee109c 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h index fa1b363b09..790e293b38 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h index d46069013c..e499c57c14 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h index a7a83c5d56..213ab3f996 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h index 772c0cdbb8..c419980637 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h index af80fffe95..b6feac2fd7 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h index f4cee56c83..b859291059 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h index b5c7aa1090..9e55f5e4e6 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h index 0ef674bcdb..cd75084a43 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h index 443f86788c..88dfdb7c4e 100644 --- a/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h +++ b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h index 1e7597be4b..85959ad83a 100644 --- a/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h +++ b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h @@ -37,6 +37,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h index 86b721fb5a..ddfcc5abfe 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h index c135991192..a576cc49f2 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h index 27c818be48..f55cf0fa0a 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h index a37ee5f510..397b7403a3 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h index 3e977b5260..38d729a0dc 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h index ae210445cc..9b06c567fe 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h index b51cc10509..9fb384f92a 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h index d1f60cffbe..dcac0b5af7 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h index d068d4448c..8c867806c7 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h index bb274f99da..d1b29f72f5 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h index 35cc0f816a..a434a9b87e 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h index 8a52a8e437..cacdf58b5b 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h index 5e50a0f6ad..efa9026e5c 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h index 6f50ef2b48..fcf3d4ec24 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h index a7d01131db..e49cf96a4a 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h index 8417d96303..068f96bb82 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h index f84c4d339f..aafbb0d401 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h index cde77fa9e2..102efa868b 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h index 7c1fd4cc3d..ecfbcecd0b 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h @@ -37,6 +37,6 @@ /* Author: David V. Lu!! */ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h index 13564454bc..ada6542a5f 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h @@ -38,6 +38,6 @@ #pragma once -#pragma message(".h header is obsolete. Please use the .hpp") +#pragma message(".h header is obsolete. Please use the .hpp header instead.") #include From a10a31ae7a0895680e25e086778ae33449fc9ef8 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Tue, 26 Nov 2024 19:21:34 +0000 Subject: [PATCH 52/53] Removes now unused parse_args() function --- moveit/scripts/create_deprecated_headers.py | 8 -------- 1 file changed, 8 deletions(-) diff --git a/moveit/scripts/create_deprecated_headers.py b/moveit/scripts/create_deprecated_headers.py index 73bf78135f..e72240b5a8 100755 --- a/moveit/scripts/create_deprecated_headers.py +++ b/moveit/scripts/create_deprecated_headers.py @@ -95,14 +95,6 @@ def contents(self) -> str: return "\n\n".join(items) + "\n" -def parse_args(args: List) -> bool: - n_args = len(sys.argv) - if n_args > 2: - sys.exit("Usage: ./create_deprecated_headers [--apply]") - apply = "--apply" == sys.argv[1] if n_args == 2 else False - return apply - - class HeaderSummary: def __init__(self, n_processed_hpps: int, bad_hpps: List[str]): self.n_processed_hpps = n_processed_hpps From 04f375f79bb74fcaa5c9ab421d7517e6502cb0d4 Mon Sep 17 00:00:00 2001 From: Tom Noble Date: Thu, 28 Nov 2024 18:24:38 +0000 Subject: [PATCH 53/53] Updates .h disclaimer with more info. Regenerates headers. --- moveit/scripts/create_deprecated_headers.py | 21 ++++++++++++++++--- .../collision_detector_allocator_allvalid.h | 14 ++++++++++--- .../allvalid/collision_env_allvalid.h | 14 ++++++++++--- .../collision_detection/collision_common.h | 14 ++++++++++--- .../collision_detector_allocator.h | 14 ++++++++++--- .../collision_detection/collision_env.h | 14 ++++++++++--- .../collision_detection/collision_matrix.h | 14 ++++++++++--- .../collision_octomap_filter.h | 14 ++++++++++--- .../collision_detection/collision_plugin.h | 14 ++++++++++--- .../collision_plugin_cache.h | 14 ++++++++++--- .../collision_detection/collision_tools.h | 14 ++++++++++--- .../collision_detection/occupancy_map.h | 14 ++++++++++--- .../test_collision_common_panda.h | 14 ++++++++++--- .../test_collision_common_pr2.h | 14 ++++++++++--- .../moveit/collision_detection/world.h | 14 ++++++++++--- .../moveit/collision_detection/world_diff.h | 14 ++++++++++--- .../bullet_integration/basic_types.h | 14 ++++++++++--- .../bullet_integration/bullet_bvh_manager.h | 14 ++++++++++--- .../bullet_cast_bvh_manager.h | 14 ++++++++++--- .../bullet_discrete_bvh_manager.h | 14 ++++++++++--- .../bullet_integration/bullet_utils.h | 14 ++++++++++--- .../contact_checker_common.h | 14 ++++++++++--- .../bullet_integration/ros_bullet_utils.h | 14 ++++++++++--- .../collision_detector_allocator_bullet.h | 14 ++++++++++--- .../collision_detector_bullet_plugin_loader.h | 14 ++++++++++--- .../collision_env_bullet.h | 14 ++++++++++--- .../collision_common.h | 14 ++++++++++--- .../collision_detector_allocator_fcl.h | 14 ++++++++++--- .../collision_detector_fcl_plugin_loader.h | 14 ++++++++++--- .../collision_env_fcl.h | 14 ++++++++++--- .../collision_detection_fcl/fcl_compat.h | 14 ++++++++++--- .../collision_common_distance_field.h | 14 ++++++++++--- ...lision_detector_allocator_distance_field.h | 14 ++++++++++--- .../collision_detector_allocator_hybrid.h | 14 ++++++++++--- .../collision_distance_field_types.h | 14 ++++++++++--- .../collision_env_distance_field.h | 14 ++++++++++--- .../collision_env_hybrid.h | 14 ++++++++++--- .../constraint_samplers/constraint_sampler.h | 14 ++++++++++--- .../constraint_sampler_allocator.h | 14 ++++++++++--- .../constraint_sampler_manager.h | 14 ++++++++++--- .../constraint_sampler_tools.h | 14 ++++++++++--- .../default_constraint_samplers.h | 14 ++++++++++--- .../union_constraint_sampler.h | 14 ++++++++++--- .../controller_manager/controller_manager.h | 14 ++++++++++--- .../moveit/distance_field/distance_field.h | 14 ++++++++++--- .../distance_field/find_internal_points.h | 14 ++++++++++--- .../propagation_distance_field.h | 14 ++++++++++--- .../moveit/distance_field/voxel_grid.h | 14 ++++++++++--- .../moveit/dynamics_solver/dynamics_solver.h | 14 ++++++++++--- .../include/moveit/exceptions/exceptions.h | 14 ++++++++++--- .../kinematic_constraint.h | 14 ++++++++++--- .../moveit/kinematic_constraints/utils.h | 14 ++++++++++--- .../moveit/kinematics_base/kinematics_base.h | 14 ++++++++++--- .../kinematics_metrics/kinematics_metrics.h | 14 ++++++++++--- .../include/moveit/macros/class_forward.h | 14 ++++++++++--- .../include/moveit/macros/console_colors.h | 14 ++++++++++--- .../include/moveit/macros/declare_ptr.h | 14 ++++++++++--- .../acceleration_filter.h | 14 ++++++++++--- .../butterworth_filter.h | 14 ++++++++++--- .../online_signal_smoothing/ruckig_filter.h | 14 ++++++++++--- .../smoothing_base_class.h | 14 ++++++++++--- .../planning_interface/planning_interface.h | 14 ++++++++++--- .../planning_interface/planning_request.h | 14 ++++++++++--- .../planning_request_adapter.h | 14 ++++++++++--- .../planning_interface/planning_response.h | 14 ++++++++++--- .../planning_response_adapter.h | 14 ++++++++++--- .../moveit/planning_scene/planning_scene.h | 14 ++++++++++--- .../include/moveit/robot_model/aabb.h | 14 ++++++++++--- .../moveit/robot_model/fixed_joint_model.h | 14 ++++++++++--- .../moveit/robot_model/floating_joint_model.h | 14 ++++++++++--- .../include/moveit/robot_model/joint_model.h | 14 ++++++++++--- .../moveit/robot_model/joint_model_group.h | 14 ++++++++++--- .../include/moveit/robot_model/link_model.h | 14 ++++++++++--- .../moveit/robot_model/planar_joint_model.h | 14 ++++++++++--- .../robot_model/prismatic_joint_model.h | 14 ++++++++++--- .../moveit/robot_model/revolute_joint_model.h | 14 ++++++++++--- .../include/moveit/robot_model/robot_model.h | 14 ++++++++++--- .../moveit/robot_state/attached_body.h | 14 ++++++++++--- .../robot_state/cartesian_interpolator.h | 14 ++++++++++--- .../include/moveit/robot_state/conversions.h | 14 ++++++++++--- .../include/moveit/robot_state/robot_state.h | 14 ++++++++++--- .../robot_trajectory/robot_trajectory.h | 14 ++++++++++--- .../ruckig_traj_smoothing.h | 14 ++++++++++--- .../time_optimal_trajectory_generation.h | 14 ++++++++++--- .../time_parameterization.h | 14 ++++++++++--- .../trajectory_processing/trajectory_tools.h | 14 ++++++++++--- .../include/moveit/transforms/transforms.h | 14 ++++++++++--- .../include/moveit/utils/eigen_test_utils.h | 14 ++++++++++--- .../include/moveit/utils/lexical_casts.h | 14 ++++++++++--- .../utils/include/moveit/utils/logger.h | 14 ++++++++++--- .../include/moveit/utils/message_checks.h | 14 ++++++++++--- .../include/moveit/utils/moveit_error_code.h | 14 ++++++++++--- .../utils/include/moveit/utils/rclcpp_utils.h | 14 ++++++++++--- .../moveit/utils/robot_model_test_utils.h | 14 ++++++++++--- .../cached_ik_kinematics_plugin-inl.h | 14 ++++++++++--- .../cached_ik_kinematics_plugin.h | 14 ++++++++++--- .../detail/GreedyKCenters.h | 14 ++++++++++--- .../detail/NearestNeighbors.h | 14 ++++++++++--- .../detail/NearestNeighborsGNAT.h | 14 ++++++++++--- .../chainiksolver_vel_mimic_svd.h | 14 ++++++++++--- .../kdl_kinematics_plugin/joint_mimic.h | 14 ++++++++++--- .../kdl_kinematics_plugin.h | 14 ++++++++++--- .../srv_kinematics_plugin.h | 14 ++++++++++--- .../include/chomp_interface/chomp_interface.h | 14 ++++++++++--- .../chomp_interface/chomp_planning_context.h | 14 ++++++++++--- .../include/chomp_motion_planner/chomp_cost.h | 14 ++++++++++--- .../chomp_motion_planner/chomp_optimizer.h | 14 ++++++++++--- .../chomp_motion_planner/chomp_parameters.h | 14 ++++++++++--- .../chomp_motion_planner/chomp_planner.h | 14 ++++++++++--- .../chomp_motion_planner/chomp_trajectory.h | 14 ++++++++++--- .../chomp_motion_planner/chomp_utils.h | 14 ++++++++++--- .../multivariate_gaussian.h | 14 ++++++++++--- .../detail/constrained_goal_sampler.h | 14 ++++++++++--- .../detail/constrained_sampler.h | 14 ++++++++++--- .../detail/constraint_approximations.h | 14 ++++++++++--- .../detail/constraints_library.h | 14 ++++++++++--- .../moveit/ompl_interface/detail/goal_union.h | 14 ++++++++++--- .../ompl_interface/detail/ompl_constraints.h | 14 ++++++++++--- .../detail/projection_evaluators.h | 14 ++++++++++--- .../detail/state_validity_checker.h | 14 ++++++++++--- .../detail/threadsafe_state_storage.h | 14 ++++++++++--- .../model_based_planning_context.h | 14 ++++++++++--- .../moveit/ompl_interface/ompl_interface.h | 14 ++++++++++--- .../constrained_planning_state_space.h | 14 ++++++++++--- ...constrained_planning_state_space_factory.h | 14 ++++++++++--- .../joint_space/joint_model_state_space.h | 14 ++++++++++--- .../joint_model_state_space_factory.h | 14 ++++++++++--- .../model_based_state_space.h | 14 ++++++++++--- .../model_based_state_space_factory.h | 14 ++++++++++--- .../work_space/pose_model_state_space.h | 14 ++++++++++--- .../pose_model_state_space_factory.h | 14 ++++++++++--- .../ompl_interface/planning_context_manager.h | 14 ++++++++++--- .../include/joint_limits_copy/joint_limits.h | 14 ++++++++++--- .../joint_limits_copy/joint_limits_rosparam.h | 14 ++++++++++--- .../capability_names.h | 14 ++++++++++--- .../cartesian_trajectory.h | 14 ++++++++++--- .../cartesian_trajectory_point.h | 14 ++++++++++--- .../command_list_manager.h | 14 ++++++++++--- .../joint_limits_aggregator.h | 14 ++++++++++--- .../joint_limits_container.h | 14 ++++++++++--- .../joint_limits_extension.h | 14 ++++++++++--- .../joint_limits_interface_extension.h | 14 ++++++++++--- .../joint_limits_validator.h | 14 ++++++++++--- .../limits_container.h | 14 ++++++++++--- .../move_group_sequence_action.h | 14 ++++++++++--- .../move_group_sequence_service.h | 14 ++++++++++--- .../path_circle_generator.h | 14 ++++++++++--- .../pilz_industrial_motion_planner.h | 14 ++++++++++--- .../plan_components_builder.h | 14 ++++++++++--- .../planning_context_base.h | 14 ++++++++++--- .../planning_context_circ.h | 14 ++++++++++--- .../planning_context_lin.h | 14 ++++++++++--- .../planning_context_loader.h | 14 ++++++++++--- .../planning_context_loader_circ.h | 14 ++++++++++--- .../planning_context_loader_lin.h | 14 ++++++++++--- .../planning_context_loader_ptp.h | 14 ++++++++++--- .../planning_context_ptp.h | 14 ++++++++++--- .../planning_exceptions.h | 14 ++++++++++--- .../tip_frame_getter.h | 14 ++++++++++--- .../trajectory_blend_request.h | 14 ++++++++++--- .../trajectory_blend_response.h | 14 ++++++++++--- .../trajectory_blender.h | 14 ++++++++++--- .../trajectory_blender_transition_window.h | 14 ++++++++++--- .../trajectory_functions.h | 14 ++++++++++--- .../trajectory_generation_exceptions.h | 14 ++++++++++--- .../trajectory_generator.h | 14 ++++++++++--- .../trajectory_generator_circ.h | 14 ++++++++++--- .../trajectory_generator_lin.h | 14 ++++++++++--- .../trajectory_generator_ptp.h | 14 ++++++++++--- .../velocity_profile_atrap.h | 14 ++++++++++--- .../async_test.h | 14 ++++++++++--- .../basecmd.h | 14 ++++++++++--- .../cartesianconfiguration.h | 14 ++++++++++--- .../cartesianpathconstraintsbuilder.h | 14 ++++++++++--- .../center.h | 14 ++++++++++--- .../checks.h | 14 ++++++++++--- .../circ.h | 14 ++++++++++--- .../circ_auxiliary_types.h | 14 ++++++++++--- .../circauxiliary.h | 14 ++++++++++--- .../command_types_typedef.h | 14 ++++++++++--- .../default_values.h | 14 ++++++++++--- .../exception_types.h | 14 ++++++++++--- .../goalconstraintsmsgconvertible.h | 14 ++++++++++--- .../gripper.h | 14 ++++++++++--- .../interim.h | 14 ++++++++++--- .../jointconfiguration.h | 14 ++++++++++--- .../lin.h | 14 ++++++++++--- .../motioncmd.h | 14 ++++++++++--- .../motionplanrequestconvertible.h | 14 ++++++++++--- .../ptp.h | 14 ++++++++++--- .../robotconfiguration.h | 14 ++++++++++--- .../robotstatemsgconvertible.h | 14 ++++++++++--- .../sequence.h | 14 ++++++++++--- .../testdata_loader.h | 14 ++++++++++--- .../xml_constants.h | 14 ++++++++++--- .../xml_testdata_loader.h | 14 ++++++++++--- .../stomp_moveit/conversion_functions.h | 14 ++++++++++--- .../include/stomp_moveit/cost_functions.h | 14 ++++++++++--- .../include/stomp_moveit/filter_functions.h | 14 ++++++++++--- .../stomp_moveit/math/multivariate_gaussian.h | 14 ++++++++++--- .../include/stomp_moveit/noise_generators.h | 14 ++++++++++--- .../stomp_moveit_planning_context.h | 14 ++++++++++--- .../include/stomp_moveit/stomp_moveit_task.h | 14 ++++++++++--- .../stomp_moveit/trajectory_visualization.h | 14 ++++++++++--- .../ControllerHandle.h | 14 ++++++++++--- .../action_based_controller_handle.h | 14 ++++++++++--- .../empty_controller_handle.h | 14 ++++++++++--- ...ollow_joint_trajectory_controller_handle.h | 14 ++++++++++--- .../gripper_controller_handle.h | 14 ++++++++++--- .../moveit_py/moveit_py_utils/copy_ros_msg.h | 14 ++++++++++--- .../moveit_py_utils/ros_msg_typecasters.h | 14 ++++++++++--- .../moveit/benchmarks/BenchmarkExecutor.h | 14 ++++++++++--- .../moveit/benchmarks/BenchmarkOptions.h | 14 ++++++++++--- .../global_planner/global_planner_component.h | 14 ++++++++++--- .../global_planner/global_planner_interface.h | 14 ++++++++++--- .../global_planner/moveit_planning_pipeline.h | 14 ++++++++++--- .../hybrid_planning_events.h | 14 ++++++++++--- .../hybrid_planning_manager.h | 14 ++++++++++--- .../planner_logic_interface.h | 14 ++++++++++--- .../replan_invalidated_trajectory.h | 14 ++++++++++--- .../single_plan_execution.h | 14 ++++++++++--- .../forward_trajectory.h | 14 ++++++++++--- .../moveit/local_planner/feedback_types.h | 14 ++++++++++--- .../local_constraint_solver_interface.h | 14 ++++++++++--- .../local_planner/local_planner_component.h | 14 ++++++++++--- .../trajectory_operator_interface.h | 14 ++++++++++--- .../simple_sampler.h | 14 ++++++++++--- .../moveit/move_group/capability_names.h | 14 ++++++++++--- .../moveit/move_group/move_group_capability.h | 14 ++++++++++--- .../moveit/move_group/move_group_context.h | 14 ++++++++++--- .../include/moveit_servo/collision_monitor.h | 14 ++++++++++--- .../moveit_servo/include/moveit_servo/servo.h | 14 ++++++++++--- .../include/moveit_servo/servo_node.h | 14 ++++++++++--- .../include/moveit_servo/utils/command.h | 14 ++++++++++--- .../include/moveit_servo/utils/common.h | 14 ++++++++++--- .../include/moveit_servo/utils/datatypes.h | 14 ++++++++++--- .../occupancy_map_monitor.h | 14 ++++++++++--- .../occupancy_map_monitor_middleware_handle.h | 14 ++++++++++--- .../occupancy_map_updater.h | 14 ++++++++++--- .../depth_image_octomap_updater.h | 14 ++++++++++--- .../lazy_free_space_updater.h | 14 ++++++++++--- .../mesh_filter/depth_self_filter_nodelet.h | 14 ++++++++++--- .../include/moveit/mesh_filter/filter_job.h | 14 ++++++++++--- .../include/moveit/mesh_filter/gl_mesh.h | 14 ++++++++++--- .../include/moveit/mesh_filter/gl_renderer.h | 14 ++++++++++--- .../include/moveit/mesh_filter/mesh_filter.h | 14 ++++++++++--- .../moveit/mesh_filter/mesh_filter_base.h | 14 ++++++++++--- .../include/moveit/mesh_filter/sensor_model.h | 14 ++++++++++--- .../moveit/mesh_filter/stereo_camera_model.h | 14 ++++++++++--- .../moveit/mesh_filter/transform_provider.h | 14 ++++++++++--- .../point_containment_filter/shape_mask.h | 14 ++++++++++--- .../pointcloud_octomap_updater.h | 14 ++++++++++--- .../moveit/semantic_world/semantic_world.h | 14 ++++++++++--- .../collision_plugin_loader.h | 14 ++++++++++--- .../constraint_sampler_manager_loader.h | 14 ++++++++++--- .../kinematics_plugin_loader.h | 14 ++++++++++--- .../include/moveit/moveit_cpp/moveit_cpp.h | 14 ++++++++++--- .../moveit/moveit_cpp/planning_component.h | 14 ++++++++++--- .../moveit/plan_execution/plan_execution.h | 14 ++++++++++--- .../plan_execution/plan_representation.h | 14 ++++++++++--- .../planning_pipeline/planning_pipeline.h | 14 ++++++++++--- .../plan_responses_container.h | 14 ++++++++++--- .../planning_pipeline_interfaces.h | 14 ++++++++++--- .../solution_selection_functions.h | 14 ++++++++++--- .../stopping_criterion_functions.h | 14 ++++++++++--- .../current_state_monitor.h | 14 ++++++++++--- .../current_state_monitor_middleware_handle.h | 14 ++++++++++--- .../planning_scene_monitor.h | 14 ++++++++++--- .../trajectory_monitor.h | 14 ++++++++++--- .../trajectory_monitor_middleware_handle.h | 14 ++++++++++--- .../include/moveit/rdf_loader/rdf_loader.h | 14 ++++++++++--- .../synchronized_string_parameter.h | 14 ++++++++++--- .../robot_model_loader/robot_model_loader.h | 14 ++++++++++--- .../trajectory_execution_manager.h | 14 ++++++++++--- .../common_objects.h | 14 ++++++++++--- .../move_group_interface.h | 14 ++++++++++--- .../planning_scene_interface.h | 14 ++++++++++--- .../moveit/robot_interaction/interaction.h | 14 ++++++++++--- .../robot_interaction/interaction_handler.h | 14 ++++++++++--- .../interactive_marker_helpers.h | 14 ++++++++++--- .../robot_interaction/kinematic_options.h | 14 ++++++++++--- .../robot_interaction/kinematic_options_map.h | 14 ++++++++++--- .../robot_interaction/locked_robot_state.h | 14 ++++++++++--- .../robot_interaction/robot_interaction.h | 14 ++++++++++--- .../tests/include/parameter_name_list.h | 14 ++++++++++--- .../trajectory_cache/trajectory_cache.h | 14 ++++++++++--- .../interactive_marker_display.h | 14 ++++++++++--- .../motion_planning_display.h | 14 ++++++++++--- .../motion_planning_frame.h | 14 ++++++++++--- .../motion_planning_frame_joints_widget.h | 14 ++++++++++--- .../motion_planning_param_widget.h | 14 ++++++++++--- .../background_processing.h | 14 ++++++++++--- .../planning_scene_display.h | 14 ++++++++++--- .../robot_state_display.h | 14 ++++++++++--- .../rviz_plugin_render_tools/octomap_render.h | 14 ++++++++++--- .../planning_link_updater.h | 14 ++++++++++--- .../planning_scene_render.h | 14 ++++++++++--- .../rviz_plugin_render_tools/render_shapes.h | 14 ++++++++++--- .../robot_state_visualization.h | 14 ++++++++++--- .../trajectory_panel.h | 14 ++++++++++--- .../trajectory_visualization.h | 14 ++++++++++--- .../include/ogre_helpers/mesh_shape.h | 14 ++++++++++--- .../trajectory_display.h | 14 ++++++++++--- .../moveit/warehouse/constraints_storage.h | 14 ++++++++++--- .../moveit/warehouse/moveit_message_storage.h | 14 ++++++++++--- .../moveit/warehouse/planning_scene_storage.h | 14 ++++++++++--- .../warehouse/planning_scene_world_storage.h | 14 ++++++++++--- .../include/moveit/warehouse/state_storage.h | 14 ++++++++++--- .../trajectory_constraints_storage.h | 14 ++++++++++--- .../moveit/warehouse/warehouse_connector.h | 14 ++++++++++--- .../moveit_setup_app_plugins/launch_bundle.h | 14 ++++++++++--- .../moveit_setup_app_plugins/launches.h | 14 ++++++++++--- .../launches_config.h | 14 ++++++++++--- .../launches_widget.h | 14 ++++++++++--- .../moveit_setup_app_plugins/perception.h | 14 ++++++++++--- .../perception_config.h | 14 ++++++++++--- .../perception_widget.h | 14 ++++++++++--- .../navigation_widget.h | 14 ++++++++++--- .../setup_assistant_widget.h | 14 ++++++++++--- .../control_xacro_config.h | 14 ++++++++++--- .../controller_edit_widget.h | 14 ++++++++++--- .../moveit_setup_controllers/controllers.h | 14 ++++++++++--- .../controllers_config.h | 14 ++++++++++--- .../controllers_widget.h | 14 ++++++++++--- .../included_xacro_config.h | 14 ++++++++++--- .../modified_urdf_config.h | 14 ++++++++++--- .../moveit_controllers.h | 14 ++++++++++--- .../moveit_controllers_config.h | 14 ++++++++++--- .../ros2_controllers.h | 14 ++++++++++--- .../ros2_controllers_config.h | 14 ++++++++++--- .../urdf_modifications.h | 14 ++++++++++--- .../urdf_modifications_widget.h | 14 ++++++++++--- .../author_information.h | 14 ++++++++++--- .../author_information_widget.h | 14 ++++++++++--- .../configuration_files.h | 14 ++++++++++--- .../configuration_files_widget.h | 14 ++++++++++--- .../moveit_setup_core_plugins/start_screen.h | 14 ++++++++++--- .../start_screen_widget.h | 14 ++++++++++--- .../include/moveit_setup_framework/config.h | 14 ++++++++++--- .../data/package_settings_config.h | 14 ++++++++++--- .../moveit_setup_framework/data/srdf_config.h | 14 ++++++++++--- .../moveit_setup_framework/data/urdf_config.h | 14 ++++++++++--- .../moveit_setup_framework/data_warehouse.h | 14 ++++++++++--- .../moveit_setup_framework/generated_file.h | 14 ++++++++++--- .../moveit_setup_framework/generated_time.h | 14 ++++++++++--- .../qt/double_list_widget.h | 14 ++++++++++--- .../qt/helper_widgets.h | 14 ++++++++++--- .../moveit_setup_framework/qt/rviz_panel.h | 14 ++++++++++--- .../qt/setup_step_widget.h | 14 ++++++++++--- .../qt/xml_syntax_highlighter.h | 14 ++++++++++--- .../moveit_setup_framework/setup_step.h | 14 ++++++++++--- .../moveit_setup_framework/templates.h | 14 ++++++++++--- .../moveit_setup_framework/testing_utils.h | 14 ++++++++++--- .../moveit_setup_framework/utilities.h | 14 ++++++++++--- .../moveit_setup_simulation/simulation.h | 14 ++++++++++--- .../simulation_widget.h | 14 ++++++++++--- .../collision_linear_model.h | 14 ++++++++++--- .../collision_matrix_model.h | 14 ++++++++++--- .../compute_default_collisions.h | 14 ++++++++++--- .../default_collisions.h | 14 ++++++++++--- .../default_collisions_widget.h | 14 ++++++++++--- .../moveit_setup_srdf_plugins/end_effectors.h | 14 ++++++++++--- .../end_effectors_widget.h | 14 ++++++++++--- .../group_edit_widget.h | 14 ++++++++++--- .../group_meta_config.h | 14 ++++++++++--- .../kinematic_chain_widget.h | 14 ++++++++++--- .../passive_joints.h | 14 ++++++++++--- .../passive_joints_widget.h | 14 ++++++++++--- .../planning_groups.h | 14 ++++++++++--- .../planning_groups_widget.h | 14 ++++++++++--- .../moveit_setup_srdf_plugins/robot_poses.h | 14 ++++++++++--- .../robot_poses_widget.h | 14 ++++++++++--- .../rotated_header_view.h | 14 ++++++++++--- .../moveit_setup_srdf_plugins/srdf_step.h | 14 ++++++++++--- .../virtual_joints.h | 14 ++++++++++--- .../virtual_joints_widget.h | 14 ++++++++++--- 376 files changed, 4143 insertions(+), 1128 deletions(-) diff --git a/moveit/scripts/create_deprecated_headers.py b/moveit/scripts/create_deprecated_headers.py index e72240b5a8..0680a081d9 100755 --- a/moveit/scripts/create_deprecated_headers.py +++ b/moveit/scripts/create_deprecated_headers.py @@ -38,6 +38,21 @@ from pathlib import Path +DISCLAIMER = """ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via {}, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ +""" + + class NoIncludeGuard(Exception): ERROR = "No include guard found in {}.hpp. Unable to generate pretext." @@ -86,13 +101,13 @@ class DeprecatedHeader: def __init__(self, hpp: HppFile): self.hpp = hpp self.path = hpp.path.with_suffix(".h") - self.prefix = f"/* This file was autogenerated by {Path(__file__).name} */" self.warn = '#pragma message(".h header is obsolete. Please use the .hpp header instead.")' self.contents = self.contents() def contents(self) -> str: - items = [self.prefix, self.hpp.pretext, self.warn, self.hpp.include] - return "\n\n".join(items) + "\n" + disclaimer = DISCLAIMER.format(Path(__file__).name).rstrip("\n") + items = [disclaimer, self.hpp.pretext, self.warn, self.hpp.include] + return "\n".join(items) + "\n" class HeaderSummary: diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h index f14ae1d94a..105a3d5d38 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Acorn Pooley, Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h index f6830cbd71..727a3fa794 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan, Jia Pan, Jens Petit */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h index 980f98d533..92a6034878 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h index c49049bfed..113eff6e43 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Acorn Pooley, Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h index 38f40738ea..5de5a9ee47 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan, Jens Petit */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h index 0aa197d3e9..d42591a58d 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan, E. Gil Jones */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h index 7485d9dd55..38cc245c27 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Adam Leeper */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h index d33d122484..d4fd16611e 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h index be1c89f288..488a734dbd 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin_cache.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h index 2d6f697f1f..1ade4aff95 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h b/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h index ebab3a1ac1..4622e9428b 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan, Jon Binney */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h index 6cebcf0835..29593909ff 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Jens Petit */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h index 0fb9ce2d5c..563103c5aa 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_pr2.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: E. Gil Jones */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/world.h b/moveit_core/collision_detection/include/moveit/collision_detection/world.h index af62d7c0bb..9a91e74a33 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/world.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/world.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan, Acorn Pooley, Sachin Chitta */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h b/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h index 29ede92cef..97ec35ab19 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Acorn Pooley, Ioan Sucan, Sachin Chitta */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h index 19f78b8fa8..98ef5335c8 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/basic_types.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (Apache License) * @@ -21,7 +31,5 @@ /* Author: Levi Armstrong */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h index c09ba17b69..8161abc6cf 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_bvh_manager.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD-2-Clause) * @@ -34,7 +44,5 @@ /* Authors: Levi Armstrong, Jens Petit */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h index 3ce5440a28..f650423e44 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_cast_bvh_manager.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD-2-Clause) * @@ -34,7 +44,5 @@ /* Author: Levi Armstrong, Jens Petit */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h index 42862e24f3..0fcdc7a8ef 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_discrete_bvh_manager.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD-2-Clause) * @@ -34,7 +44,5 @@ /* Author: Levi Armstrong, Jens Petit */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h index e1f47c2976..320df7d4f3 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD-2-Clause) * @@ -35,7 +45,5 @@ /* Authors: John Schulman, Levi Armstrong */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h index b3dce862fa..7df452bef4 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (Apache License) * @@ -21,7 +31,5 @@ /* Author: Levi Armstrong */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h index cf8417138c..0678d43f35 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (Apache License) * @@ -21,7 +31,5 @@ /* Author: Levi Armstrong */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h index f14d95f68f..ee177d7306 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Jens Petit */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h index 849a7652d6..67cd42a0ea 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_bullet_plugin_loader.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Jens Petit */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h index 34ef2d49a3..a1aed35c78 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Jens Petit */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h index 94c4735ba5..9f4d7152bb 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h index 0a10b9230e..f673c6a5df 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Acorn Pooley, Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h index d0634926df..3830750f37 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Bryce Willey */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h index cef67046a4..ac6229523d 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan, Jens Petit */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h index 7c0a490f34..8c649bdf7d 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Benjamin Scholz */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h index 6c0db44b20..c18155ff68 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: E. Gil Jones */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h index 5043a88023..7a4d99909c 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Acorn Pooley, Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h index c46919a022..a251248fde 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Acorn Pooley, Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h index c87441bc65..a115d416aa 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: E. Gil Jones */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h index 777e771d6c..55e15faa04 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: E. Gil Jones */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h index 79c5675b42..2374412165 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: E. Gil Jones, Jens Petit */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h index 31aa8ddd3e..629d68c425 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h index 96854a1c27..f85741bcd7 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h index b797e85bc6..3666bbdd61 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h index 08048df931..6291fe8b9b 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h index 4b14a14757..88360bb35a 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h index 40cfb1dbd4..58aa8d0f8c 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h b/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h index 9db4f0ae64..beedf3a8a5 100644 --- a/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h +++ b/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/distance_field/include/moveit/distance_field/distance_field.h b/moveit_core/distance_field/include/moveit/distance_field/distance_field.h index e2cb9761f0..08756ce37d 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/distance_field.h +++ b/moveit_core/distance_field/include/moveit/distance_field/distance_field.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Mrinal Kalakrishnan, Ken Anderson, E. Gil Jones */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h b/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h index f17e8a6945..a5f7d1b2b0 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h +++ b/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Acorn Pooley */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h b/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h index 81b2140609..b35d5dae45 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h +++ b/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Mrinal Kalakrishnan, Ken Anderson */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h b/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h index fd976c521b..3fffa6cb19 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h +++ b/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Mrinal Kalakrishnan, Acorn Pooley */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h b/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h index 59728aea0f..3cfb314a36 100644 --- a/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h +++ b/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Sachin Chitta */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/exceptions/include/moveit/exceptions/exceptions.h b/moveit_core/exceptions/include/moveit/exceptions/exceptions.h index 5eaaa848ee..5011a823c0 100644 --- a/moveit_core/exceptions/include/moveit/exceptions/exceptions.h +++ b/moveit_core/exceptions/include/moveit/exceptions/exceptions.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Acorn Pooley, Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h index 3aa43f5718..fb78e1c6ce 100644 --- a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h +++ b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h index e2c614c55f..a7462a8718 100644 --- a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h +++ b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h index 0b2181de44..9b40ba51a8 100644 --- a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h +++ b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Sachin Chitta, Dave Coleman */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h b/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h index 0c0320e89a..901b92a559 100644 --- a/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h +++ b/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Sachin Chitta */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/macros/include/moveit/macros/class_forward.h b/moveit_core/macros/include/moveit/macros/class_forward.h index 654be06053..b618646d2d 100644 --- a/moveit_core/macros/include/moveit/macros/class_forward.h +++ b/moveit_core/macros/include/moveit/macros/class_forward.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/macros/include/moveit/macros/console_colors.h b/moveit_core/macros/include/moveit/macros/console_colors.h index ae7dbe9573..be091522f4 100644 --- a/moveit_core/macros/include/moveit/macros/console_colors.h +++ b/moveit_core/macros/include/moveit/macros/console_colors.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/macros/include/moveit/macros/declare_ptr.h b/moveit_core/macros/include/moveit/macros/declare_ptr.h index 43e25e3c68..1fcca3e238 100644 --- a/moveit_core/macros/include/moveit/macros/declare_ptr.h +++ b/moveit_core/macros/include/moveit/macros/declare_ptr.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h index ff0c599ca0..bdd2b4abde 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -73,7 +83,5 @@ c --------x--- v | */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h index 34275f41f1..05bb859ab8 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -40,7 +50,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h index 59e624ac31..bd50e91ec6 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -39,7 +49,5 @@ Description: Applies jerk/acceleration/velocity limits to online motion commands */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h index 68e030d9c7..29498eefd8 100644 --- a/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h +++ b/moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/smoothing_base_class.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -39,7 +49,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h index df37b805ea..069b616503 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h index 9f59f37bc6..9664659c38 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h index fa8feb9643..ccab57105d 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -39,7 +49,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h index 6459650554..1b5e6bae2a 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h index 24bc88140e..50a786770d 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Sebastian Jahr */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h index f8ee76c3f4..682da93b7f 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan, Acorn Pooley */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/aabb.h b/moveit_core/robot_model/include/moveit/robot_model/aabb.h index e3223af591..e8f640bd0c 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/aabb.h +++ b/moveit_core/robot_model/include/moveit/robot_model/aabb.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Martin Pecka */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h index 91f937e907..751e42cc37 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h index 2986947ea8..0eba5db712 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/joint_model.h index ac0f3e5404..ea06d11e55 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/joint_model.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -38,7 +48,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h index 6271c6de66..d9e53b3061 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h +++ b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -38,7 +48,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/link_model.h b/moveit_core/robot_model/include/moveit/robot_model/link_model.h index 16ffcae4ed..4337b6ba77 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/link_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/link_model.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h index 4a7c6d45b6..b2c269981b 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h index e7b8d69a85..86908dd1d9 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h index 3de10f22c3..bdf9e1475a 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h index 22436148e8..91625baf21 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -38,7 +48,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/robot_state/include/moveit/robot_state/attached_body.h b/moveit_core/robot_state/include/moveit/robot_state/attached_body.h index b2491acd54..0bf8a61f8d 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/attached_body.h +++ b/moveit_core/robot_state/include/moveit/robot_state/attached_body.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h b/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h index 44f699f6c6..d84fe72c67 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h +++ b/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -39,7 +49,5 @@ /* Author: Ioan Sucan, Mike Lautman */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/robot_state/include/moveit/robot_state/conversions.h b/moveit_core/robot_state/include/moveit/robot_state/conversions.h index 98cc197734..a6817510c8 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/conversions.h +++ b/moveit_core/robot_state/include/moveit/robot_state/conversions.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan, Dave Coleman */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h index 7d52ff1e42..5b7867273f 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h +++ b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -38,7 +48,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h index 0dba39fc91..d1763c1a7c 100644 --- a/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h +++ b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan, Adam Leeper */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h index b170a8c0f7..b383610ac4 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /******************************************************************************* * BSD 3-Clause License * @@ -36,7 +46,5 @@ /* Author: Jack Center, Wyatt Rees, Andy Zelenak, Stephanie Eng */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h index a696e49a06..2481703ba0 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /* * Copyright (c) 2011-2012, Georgia Tech Research Corporation * All rights reserved. @@ -39,7 +49,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h index 4a38effafb..9d73c3f9a7 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_parameterization.h @@ -1,7 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h index 357ec23b0f..82944432e8 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/transforms/include/moveit/transforms/transforms.h b/moveit_core/transforms/include/moveit/transforms/transforms.h index 6bb5724953..df62410bf2 100644 --- a/moveit_core/transforms/include/moveit/transforms/transforms.h +++ b/moveit_core/transforms/include/moveit/transforms/transforms.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/utils/include/moveit/utils/eigen_test_utils.h b/moveit_core/utils/include/moveit/utils/eigen_test_utils.h index 0bb942c5db..235d4096d9 100644 --- a/moveit_core/utils/include/moveit/utils/eigen_test_utils.h +++ b/moveit_core/utils/include/moveit/utils/eigen_test_utils.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Robert Haschke */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/utils/include/moveit/utils/lexical_casts.h b/moveit_core/utils/include/moveit/utils/lexical_casts.h index 110051fec4..f698d2eca8 100644 --- a/moveit_core/utils/include/moveit/utils/lexical_casts.h +++ b/moveit_core/utils/include/moveit/utils/lexical_casts.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Simon Schmeisser */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/utils/include/moveit/utils/logger.h b/moveit_core/utils/include/moveit/utils/logger.h index 10ce652921..7f2c3490fa 100644 --- a/moveit_core/utils/include/moveit/utils/logger.h +++ b/moveit_core/utils/include/moveit/utils/logger.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Tyler Weaver */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/utils/include/moveit/utils/message_checks.h b/moveit_core/utils/include/moveit/utils/message_checks.h index dfbb2f8614..83b721c2dd 100644 --- a/moveit_core/utils/include/moveit/utils/message_checks.h +++ b/moveit_core/utils/include/moveit/utils/message_checks.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Michael 'v4hn' Goerner */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/utils/include/moveit/utils/moveit_error_code.h b/moveit_core/utils/include/moveit/utils/moveit_error_code.h index a18743f139..c7646d1832 100644 --- a/moveit_core/utils/include/moveit/utils/moveit_error_code.h +++ b/moveit_core/utils/include/moveit/utils/moveit_error_code.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/utils/include/moveit/utils/rclcpp_utils.h b/moveit_core/utils/include/moveit/utils/rclcpp_utils.h index f17e8ea8ef..0e8174d79a 100644 --- a/moveit_core/utils/include/moveit/utils/rclcpp_utils.h +++ b/moveit_core/utils/include/moveit/utils/rclcpp_utils.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /* * Copyright (C) 2009, Willow Garage, Inc. * @@ -28,7 +38,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h b/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h index 43b9fbd50e..337086d241 100644 --- a/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h +++ b/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -38,7 +48,5 @@ /** \brief convenience functions and classes used for making simple robot models for testing. */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h index ff35846101..a30943df99 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin-inl.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Mark Moll */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h index b0106ce66c..994f97224a 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Mark Moll */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h index 0ef8eb1c36..bcabf09cf2 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -39,7 +49,5 @@ // This file is a slightly modified version of #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h index 406f3035e2..9d5afa103e 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -39,7 +49,5 @@ // This file is a slightly modified version of #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h index e1b6d45f64..d6f2edaa17 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -39,7 +49,5 @@ // This file is a slightly modified version of #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h index 919a770bad..883be380eb 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h +++ b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ // Copyright (C) 2007 Ruben Smits // Version: 1.0 @@ -26,7 +36,5 @@ // Copyright (C) 2013 Sachin Chitta, Willow Garage #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h index 0dea3f60f9..ff60467ac2 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h +++ b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Sachin Chitta */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h index ee0c94edf4..6f12af21ff 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h +++ b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Sachin Chitta, David Lu!!, Ugo Cupcic */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h b/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h index c920152168..a99cf7c1f0 100644 --- a/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h +++ b/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -42,7 +52,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h index 11a21a4f5b..0ff890315f 100644 --- a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h +++ b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: E. Gil Jones */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h index 1e0544b0f2..30db2519ad 100644 --- a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h +++ b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Chittaranjan Srinivas Swaminathan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h index a69ff94bc6..35954d379f 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Mrinal Kalakrishnan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h index f358e2f3f5..d8b69aeeb4 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Mrinal Kalakrishnan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h index c1f4d0969c..c6391cf9cc 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -40,7 +50,5 @@ #include #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h index 6f9b71283e..dd70021f71 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: E. Gil Jones */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h index b065aecaf9..3c9ce483df 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Mrinal Kalakrishnan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h index 499a90b227..db0f0ca80b 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Mrinal Kalakrishnan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h index 7354558ac7..ece45e35d6 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Mrinal Kalakrishnan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h index aabfe63422..1158247890 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h index b04f23d551..1484dfed90 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h index b3c0bc9ebe..e72f03a660 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h index 4d65cfe9c3..f349982470 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h index bb5fc103b0..33ba25563b 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/goal_union.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h index 8f5c851170..7c4321bd30 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/ompl_constraints.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Jeroen De Maeyer, Boston Cleek */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h index 69b7187c9e..b53cb107c8 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h index 24e54c0a17..83383b065a 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -48,7 +58,5 @@ * **/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h index 4f700ff6a3..31621f821d 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h index b032e745fe..43770b293a 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h index 25c628318a..c8e023d5c5 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h index fea175ca70..59803884f7 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Jeroen De Maeyer */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h index 81ec299d95..e8761e8092 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/constrained_planning_state_space_factory.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -38,7 +48,5 @@ /* Mostly copied from Ioan Sucan's code */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h index 1129ba99d4..cfe7a5cb74 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h index ad61bcffb3..06919287f1 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h index ce116bfb9f..37dcc757dc 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h index ac9319f476..bc63210279 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h index 2778536547..86d15a254b 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h index f7679a896e..ff67a81f36 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h index 31d23e9507..4bcf8dc192 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h index 854aa32805..301e25fa8b 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ // Copyright 2020 PAL Robotics S.L. // // Licensed under the Apache License, Version 2.0 (the "License"); @@ -17,7 +27,5 @@ /// \author Adolfo Rodriguez Tsouroukdissian #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h index 18d39bed10..7918de9fbe 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ // Copyright 2020 PAL Robotics S.L. // // Licensed under the Apache License, Version 2.0 (the "License"); @@ -17,7 +27,5 @@ /// \author Adolfo Rodriguez Tsouroukdissian #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h index d6655eb8b3..2217fab1c2 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/capability_names.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h index c2778f2cc8..7aab35f9d7 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h index 5754337126..0c9cb3bc0d 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/cartesian_trajectory_point.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h index 6bf6136259..a5beedcb6b 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h index 39a36e1223..30be1fcef5 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_aggregator.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h index 0419683d73..03dd00ab22 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_container.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h index cfaf5c78c4..8e46127033 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_extension.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h index 813357bc67..5f8fd673af 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_interface_extension.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h index eefa8cecd1..5e63f6ddb9 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/joint_limits_validator.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h index 5c8160a2b8..5a038a1d45 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/limits_container.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h index 5676de3c2a..b016a59076 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_action.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h index 60b67d2643..285dd92105 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/move_group_sequence_service.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h index 98f3b8ba2b..6004eec016 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/path_circle_generator.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h index 59994f0a3f..6e1ede489e 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h index f3df93cb35..c0c20faf2a 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h index 9dab16b5c4..449993e37f 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h index 5f55bacd4d..d89226c9ff 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_circ.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h index a19e8d39f5..5fde25977c 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_lin.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h index ab9de2d1c0..3812eefe6d 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h index f423e48787..6e365f4ce8 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h index 6b23d4f073..99f97852e0 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h index 590f3f687a..877d301689 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h index 690eed96dc..829a43b1c7 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_ptp.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h index 42e96c0006..c1a46f0e51 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_exceptions.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h index 05a40515d8..94a493fe16 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/tip_frame_getter.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h index 6e65d4c823..c0e8559256 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_request.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h index 1bbc0cf177..67e7fa32e2 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blend_response.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h index ac8c479466..921a823d43 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h index 5b98e893b1..61e598d162 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h index d4d530001c..f66bf3ac50 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h index 4d0d963fd4..3feaeac67d 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generation_exceptions.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h index ce2d27417f..fb7844fd82 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h index 1eb091e23c..3dd4e9828b 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h index 28bb31be2b..fbf685c7f2 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h index 3df3259582..3404a24268 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h index 23bbc1218e..b499ddf931 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/velocity_profile_atrap.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h index b20ecd3407..bb84bbcac6 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/async_test.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /* * Copyright (c) 2018 Pilz GmbH & Co. KG * @@ -17,7 +27,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h index 60943b75be..702a79adc6 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/basecmd.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h index 9f090df6fd..350c54f5b0 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h index f293dfd801..72f8210465 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianpathconstraintsbuilder.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h index d1a63e40fd..de30af49eb 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/center.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h index 61dec12e0e..07c15ca8a8 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/checks.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h index be0de6232a..2de70b4407 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h index 7740480e42..9420daeb3a 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circ_auxiliary_types.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h index 136e29b05c..07af3992a7 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/circauxiliary.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h index bcb07fbc4e..be492d4406 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h index 67868fafa6..53e2ec5b47 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/default_values.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h index 982da25593..cc8e21b40f 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/exception_types.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h index 7d73eeab35..118128f15c 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/goalconstraintsmsgconvertible.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h index 4c916dc200..fd3d01bec1 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/gripper.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h index a632cc5648..2e2e3df04d 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/interim.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h index b7bb752db5..1d9f70c06b 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/jointconfiguration.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h index cb2a80f896..03faea1f5d 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/lin.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h index d55835ab43..ffca77b320 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motioncmd.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h index f64f71b75d..b8dae56d66 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/motionplanrequestconvertible.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h index 419eb886e9..21429ca89a 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/ptp.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h index dbf085b973..c7e6e521e9 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotconfiguration.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h index ed3e186fc4..c5a05d8ab3 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/robotstatemsgconvertible.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h index 6ea7364a94..69ef4701f5 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h index df1a082dfb..a975a76663 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/testdata_loader.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h index b84c542579..35a42a250a 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_constants.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h index 9517b28f32..24d2d23744 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h b/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h index 60bdfd5bda..a4f6a35503 100644 --- a/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h +++ b/moveit_planners/stomp/include/stomp_moveit/conversion_functions.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -40,7 +50,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/stomp/include/stomp_moveit/cost_functions.h b/moveit_planners/stomp/include/stomp_moveit/cost_functions.h index 13c98008f5..125fa9068c 100644 --- a/moveit_planners/stomp/include/stomp_moveit/cost_functions.h +++ b/moveit_planners/stomp/include/stomp_moveit/cost_functions.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -40,7 +50,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/stomp/include/stomp_moveit/filter_functions.h b/moveit_planners/stomp/include/stomp_moveit/filter_functions.h index 9968470c5c..5d1872c522 100644 --- a/moveit_planners/stomp/include/stomp_moveit/filter_functions.h +++ b/moveit_planners/stomp/include/stomp_moveit/filter_functions.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -40,7 +50,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h b/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h index 68edd4c4e8..32efbac874 100644 --- a/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h +++ b/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -40,7 +50,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/stomp/include/stomp_moveit/noise_generators.h b/moveit_planners/stomp/include/stomp_moveit/noise_generators.h index 1b7c12ddf0..c27ac1c1d6 100644 --- a/moveit_planners/stomp/include/stomp_moveit/noise_generators.h +++ b/moveit_planners/stomp/include/stomp_moveit/noise_generators.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -40,7 +50,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h index 5e59826ffc..1bc31847bf 100644 --- a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h +++ b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_planning_context.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -40,7 +50,5 @@ **/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h index b62661212c..9781a0c10b 100644 --- a/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h +++ b/moveit_planners/stomp/include/stomp_moveit/stomp_moveit_task.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -55,7 +65,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h b/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h index 766883eda3..ab9c11003d 100644 --- a/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h +++ b/moveit_planners/stomp/include/stomp_moveit/trajectory_visualization.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -40,7 +50,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h b/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h index 77ca596ddc..fe3f29d1a1 100644 --- a/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h +++ b/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Mathias Lüdtke */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h index f1886c97dc..ade93c7118 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -38,7 +48,5 @@ /* Author: Michael Ferguson, Ioan Sucan, E. Gil Jones */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h index 556616144d..bae97d1949 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/empty_controller_handle.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Paul Gesel */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h index e4ed2fddf8..f51462cb8c 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -38,7 +48,5 @@ /* Author: Michael Ferguson, Ioan Sucan, E. Gil Jones */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h index d86f8dd8a3..761eaf3ef9 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -38,7 +48,5 @@ /* Author: Michael Ferguson, Ioan Sucan, E. Gil Jones */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h index 2ffa98fbe9..6554326a71 100644 --- a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h +++ b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/copy_ros_msg.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Peter David Fagan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h index dec636ff47..d5d06c50a3 100644 --- a/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h +++ b/moveit_py/src/moveit/moveit_py_utils/include/moveit_py/moveit_py_utils/ros_msg_typecasters.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Peter David Fagan, Robert Haschke */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h index 302be23035..75c1073985 100644 --- a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h +++ b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ryan Luna */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h index 58d9784dff..63e4c52e48 100644 --- a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h +++ b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ryan Luna */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h index 562a060ebb..2bf0031f55 100644 --- a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h +++ b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_component.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -39,7 +49,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h index 4bcb507cc9..8fba00fd4c 100644 --- a/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h +++ b/moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -40,7 +50,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h b/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h index a707923b29..f19a59ba06 100644 --- a/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h +++ b/moveit_ros/hybrid_planning/global_planner/global_planner_plugins/include/moveit/global_planner/moveit_planning_pipeline.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -38,7 +48,5 @@ Description: Global planner plugin that utilizes MoveIt's planning pipeline accessed via the MoveItCpp API*/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h index 4f1c64b02a..3e1cd37d04 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_events.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -38,7 +48,5 @@ Description: Defines events that could occur during hybrid planning */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h index a43c8ac6e4..05c9a5f22e 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/hybrid_planning_manager.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -39,7 +49,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h index ea0876ac24..bfd0f87a98 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -39,7 +49,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h index 29d651e91b..6ba28008e2 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/replan_invalidated_trajectory.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -41,7 +51,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h index 001139a0ee..66bef5d62d 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/planner_logic_plugins/include/moveit/planner_logic_plugins/single_plan_execution.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -40,7 +50,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h b/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h index c8e38dd928..2a6b43508c 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h +++ b/moveit_ros/hybrid_planning/local_planner/local_constraint_solver_plugins/include/moveit/local_constraint_solver_plugins/forward_trajectory.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -41,7 +51,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h index 86d70f3a2b..6d3003c88f 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/feedback_types.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -40,7 +50,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h index 423f9cc6a3..ddb293494a 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -39,7 +49,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h index 1f7b534158..f570897c4a 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_planner_component.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -40,7 +50,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h index 4100683b60..e1a0441812 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -39,7 +49,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h b/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h index 45be7faa22..9de076fd83 100644 --- a/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h +++ b/moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/include/moveit/trajectory_operator_plugins/simple_sampler.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -41,7 +51,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/move_group/include/moveit/move_group/capability_names.h b/moveit_ros/move_group/include/moveit/move_group/capability_names.h index db6a192c61..bbc1d20b99 100644 --- a/moveit_ros/move_group/include/moveit/move_group/capability_names.h +++ b/moveit_ros/move_group/include/moveit/move_group/capability_names.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h b/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h index 9c6438ba52..836721939e 100644 --- a/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h +++ b/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/move_group/include/moveit/move_group/move_group_context.h b/moveit_ros/move_group/include/moveit/move_group/move_group_context.h index 7d938687fb..83be3652e0 100644 --- a/moveit_ros/move_group/include/moveit/move_group/move_group_context.h +++ b/moveit_ros/move_group/include/moveit/move_group/move_group_context.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h b/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h index ac61f35e65..4a0844ec61 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/collision_monitor.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /******************************************************************************* * BSD 3-Clause License * @@ -42,7 +52,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/servo.h b/moveit_ros/moveit_servo/include/moveit_servo/servo.h index 23d9786d3f..08f0a9bcf4 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/servo.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/servo.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /******************************************************************************* * BSD 3-Clause License * @@ -42,7 +52,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h b/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h index e85910edf3..9887d0742f 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/servo_node.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /******************************************************************************* * BSD 3-Clause License * @@ -42,7 +52,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h b/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h index aecb55585a..c42f449d41 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/utils/command.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /******************************************************************************* * BSD 3-Clause License * @@ -42,7 +52,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h b/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h index d5d3d8d283..1933c2d101 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/utils/common.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /******************************************************************************* * BSD 3-Clause License * @@ -42,7 +52,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h b/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h index 51311c7bf2..18d364ed57 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/utils/datatypes.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /******************************************************************************* * BSD 3-Clause License * @@ -42,7 +52,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h index 2cfa100a12..e510834c2a 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan, Jon Binney */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h index 3749b19609..524be9f63c 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor_middleware_handle.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Tyler Weaver */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h index cf5166a878..d85ae969f0 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan, Jon Binney */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h b/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h index fd53b22f0e..9f1b55d5b9 100644 --- a/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h +++ b/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h b/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h index ae545cb8d7..80061c02e2 100644 --- a/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h +++ b/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h index 7183540b5b..2ea6b35849 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Suat Gedikli */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h index fdb3a5e89f..eff3b19d8b 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Suat Gedikli */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h index b580d22b12..5859bb5cbc 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Suat Gedikli */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h index 0221343703..eafb2cf27a 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Suat Gedikli */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h index 5e741b17a0..d663157e8a 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Suat Gedikli */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h index 16e874fb64..2ae3774d69 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Suat Gedikli */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h index d8cfb0ff3d..2964c99bd6 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Suat Gedikli */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h index 7b05f58e0e..3cf7f4553a 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Suat Gedikli */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h index be0d457f7d..3a481ef73e 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Suat Gedikli */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h b/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h index e053a75a7f..17c13dee53 100644 --- a/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h +++ b/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h b/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h index 65a1835a33..83f675ddfc 100644 --- a/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h +++ b/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Jon Binney, Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h index 606d919539..479855553d 100644 --- a/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h +++ b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Sachin Chitta */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h b/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h index b53a58d9bb..6092f7e330 100644 --- a/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h +++ b/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h b/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h index 501aca2da3..754bad6229 100644 --- a/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h +++ b/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h b/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h index 4fac35d82f..2d39f11e3e 100644 --- a/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h +++ b/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan, Dave Coleman */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h index ef53158a73..144ddaad6c 100644 --- a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h +++ b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/moveit_cpp.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -40,7 +50,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h index f396eebbc4..ac6928f664 100644 --- a/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h +++ b/moveit_ros/planning/moveit_cpp/include/moveit/moveit_cpp/planning_component.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -38,7 +48,5 @@ Desc: API for planning and execution capabilities of a JointModelGroup */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h index 9073883eef..999562f7e4 100644 --- a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h +++ b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h index 3457baa5c6..1773e12637 100644 --- a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h +++ b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h index 2cb45c37be..1ab8d3ff42 100644 --- a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h +++ b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -40,7 +50,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h index bf82ed1cb5..fb2369713f 100644 --- a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/plan_responses_container.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -38,7 +48,5 @@ Desc: A thread safe container to store motion plan responses */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h index 8353e03903..1e7fefa558 100644 --- a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/planning_pipeline_interfaces.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -38,7 +48,5 @@ Desc: Functions to create and use a map of PlanningPipelines to solve MotionPlanRequests */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h index e693f2c5c7..bf57e5b975 100644 --- a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/solution_selection_functions.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -38,7 +48,5 @@ Desc: Solution selection function implementations */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h index 215278477d..72239439d9 100644 --- a/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h +++ b/moveit_ros/planning/planning_pipeline_interfaces/include/moveit/planning_pipeline_interfaces/stopping_criterion_functions.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -38,7 +48,5 @@ Desc: Stopping criterion function implementations */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h index 65e6b263e4..ddb74381d8 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h index 2e60ee0abe..11ed2aa69b 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor_middleware_handle.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Tyler Weaver */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h index ef159ee184..966cf41449 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h index 3b2972a7bd..2b60e485b1 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h index 72c5fa55d2..ea042840cc 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor_middleware_handle.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Abishalini Sivaraman */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h index a3e6123240..f55ce2fe60 100644 --- a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h +++ b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan, Mathias Lüdtke, Dave Coleman */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h index 16e25fa3e7..82304b6b7a 100644 --- a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h +++ b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/synchronized_string_parameter.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h b/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h index d577717cee..14aa6f0673 100644 --- a/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h +++ b/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h index 58c3d5dafd..211d09d6b8 100644 --- a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h +++ b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h b/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h index 6ae3c57b89..271fe6c6db 100644 --- a/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h +++ b/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h index e5ff7a88e6..c5a2cc62a6 100644 --- a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h +++ b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -38,7 +48,5 @@ /* Author: Ioan Sucan, Sachin Chitta */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h b/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h index 52538c7f76..632b1301c0 100644 --- a/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h +++ b/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h index 1578dfd801..79c0c12257 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Acorn Pooley */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h index 54293cdf34..22b8c872b4 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan, Adam Leeper */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h index bb71588cdb..1378d220c2 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan, Acorn Pooley, Adam Leeper */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h index 86c1961545..f73d5d10b5 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Acorn Pooley */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h index 23419669e5..dc8fca95ca 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Acorn Pooley */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h index dfb2304ad0..18d145cc33 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -38,7 +48,5 @@ /* Author: Ioan Sucan, Acorn Pooley */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h index 6080c51212..9171ad6017 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan, Adam Leeper */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/tests/include/parameter_name_list.h b/moveit_ros/tests/include/parameter_name_list.h index d8929212e7..e6fa9950cf 100644 --- a/moveit_ros/tests/include/parameter_name_list.h +++ b/moveit_ros/tests/include/parameter_name_list.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -39,7 +49,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h b/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h index a124a872c6..d2febfa95c 100644 --- a/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h +++ b/moveit_ros/trajectory_cache/include/moveit/trajectory_cache/trajectory_cache.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ // Copyright 2024 Intrinsic Innovation LLC. // // Licensed under the Apache License, Version 2.0 (the "License"); @@ -20,7 +30,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h index 475afbae12..6c5103c617 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/interactive_marker_display.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /* * Copyright (c) 2008, Willow Garage, Inc. * Copyright (c) 2019, Open Source Robotics Foundation, Inc. @@ -36,7 +46,5 @@ // marker cause by Rviz having only a single thread executor #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h index 8f198f29b6..97cbded9ef 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan, Dave Coleman, Adam Leeper, Sachin Chitta */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h index ac0b2d95cf..76730c7c12 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h index ea14effb61..2c4c6e8cbf 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Robert Haschke */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h index 5a703a100a..2777245a6b 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Robert Haschke */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h index 23680adc3e..c573328ffe 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h index 103734df79..4b778bac2e 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h b/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h index 5e35f9445c..278e0a5154 100644 --- a/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h +++ b/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h index 7c3fa4097a..a9313d9b11 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Julius Kammerl */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h index 2a9e44693f..734cef9f45 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h index b7a5019631..0932818571 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h index de5f953701..6125fb9258 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h index dc9e390318..35698767d4 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h index 83d50889a2..ba5b922d5b 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Yannick Jonetzko */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h index a4ca6a4263..a70f2a9f87 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Dave Coleman */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h index 889cc3356e..08bb84afd9 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/ogre_helpers/mesh_shape.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /* * Copyright (c) 2008, Willow Garage, Inc. * All rights reserved. @@ -30,7 +40,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h b/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h index 1d830fa91b..26cc8d0d88 100644 --- a/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h +++ b/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -39,7 +49,5 @@ */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h index d7689aebab..9e941fc033 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h index 2728c0ab3b..16aa781fca 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/moveit_message_storage.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h index 2ad6b1a06b..2308cd5aab 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h index be125d940a..59de13d41c 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h index 617c8ceffb..081edf5299 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h index b23f8c7fcf..626018eb3b 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Mario Prats, Ioan Sucan */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h b/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h index cad7b15679..14cf5ee79f 100644 --- a/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h +++ b/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: E. Gil Jones */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h index 3caac03ac5..a5fb6815a9 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launch_bundle.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -36,7 +46,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h index ee377cc1c9..b7896b7018 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -36,7 +46,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h index 34f19804f3..d8d9e896cc 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_config.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -36,7 +46,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h index 2b9c64768f..90eab15d77 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/launches_widget.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -36,7 +46,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h index 09ed271e2e..801740977a 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -36,7 +46,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h index ca38ed7319..a208e2bedc 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -36,7 +46,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h index 3b3470e592..5f7f43d729 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_widget.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -36,7 +46,5 @@ /* Author: Mohamad Ayman */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h index 7fbdef4413..2bb5b430ca 100644 --- a/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h +++ b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/navigation_widget.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Dave Coleman */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h index 807f0e9f59..c57e6ab446 100644 --- a/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h +++ b/moveit_setup_assistant/moveit_setup_assistant/include/moveit_setup_assistant/setup_assistant_widget.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Dave Coleman */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h index 4eeacbfe8f..e2b5884081 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/control_xacro_config.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h index 7e55cd1130..2720e4a71a 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controller_edit_widget.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -36,7 +46,5 @@ /* Author: Mohamad Ayman */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h index ed45a866e7..c44ac245d8 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -36,7 +46,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h index 72647016df..4314e776c4 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_config.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -36,7 +46,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h index 2f9f76cf84..a46510f27e 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers_widget.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -36,7 +46,5 @@ /* Author: Mohamad Ayman */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h index dbb5f0f5f8..7f265af80f 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/included_xacro_config.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h index 1a99f34c73..810bb80994 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/modified_urdf_config.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h index 41d6f6c8ce..1826c27f31 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h index 47ff73d8c6..2304ca4a8c 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/moveit_controllers_config.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h index 777eb911b7..b08da4f4a2 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h index d2a1c98d24..d8034f1560 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/ros2_controllers_config.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h index b546c74d3d..e392ddf966 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -36,7 +46,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h index fa6131d830..462daca3f3 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/urdf_modifications_widget.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h index bac4ccfee5..680837837c 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -36,7 +46,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h index ee833937a0..9984b5e7bc 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/author_information_widget.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Dave Coleman, Michael 'v4hn' Goerner */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h index 5634d29417..539f4ce78a 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h index 26591afdec..cf8bfb6f59 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/configuration_files_widget.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Dave Coleman */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h index 2136002c7f..4df57556a7 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h index 9f59ce62c4..244a5e8af9 100644 --- a/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h +++ b/moveit_setup_assistant/moveit_setup_core_plugins/include/moveit_setup_core_plugins/start_screen_widget.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Dave Coleman */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h index ff8c62dadf..67168733d2 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/config.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h index f2b9de8a46..f928a8b61b 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/package_settings_config.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h index 05120e5e5e..a7fa8bfae1 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/srdf_config.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -36,7 +46,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h index 37ad336a46..d3b01f4f9a 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data/urdf_config.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -35,7 +45,5 @@ *********************************************************************/ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h index 521a80ea5f..8a6cf28bed 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/data_warehouse.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -43,7 +53,5 @@ #include #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h index bd365a2e46..986a6f483d 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_file.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h index 07151ceffd..ccb3e54516 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/generated_time.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h index fe87ee109c..38eda09fd8 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/double_list_widget.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Dave Coleman */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h index 790e293b38..78463ebfe9 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/helper_widgets.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Dave Coleman */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h index e499c57c14..d79e7ed04c 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/rviz_panel.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h index 213ab3f996..253070b421 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/setup_step_widget.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Dave Coleman */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h index c419980637..5b13e57925 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/qt/xml_syntax_highlighter.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Robert Haschke */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h index b6feac2fd7..deb5540752 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h index b859291059..14134d5a81 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/templates.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -36,7 +46,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h index 9e55f5e4e6..996541d626 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/testing_utils.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h index cd75084a43..a9f5ae9cfd 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/utilities.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h index 88dfdb7c4e..c5041b864e 100644 --- a/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h +++ b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -36,7 +46,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h index 85959ad83a..5dd183e652 100644 --- a/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h +++ b/moveit_setup_assistant/moveit_setup_simulation/include/moveit_setup_simulation/simulation_widget.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -36,7 +46,5 @@ /* Author: Mohamad Ayman */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h index ddfcc5abfe..271fe9aa0e 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_linear_model.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Robert Haschke */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h index a576cc49f2..1cbab31495 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/collision_matrix_model.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Robert Haschke */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h index f55cf0fa0a..3a1a8e1d2e 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/compute_default_collisions.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Dave Coleman */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h index 397b7403a3..55120b9bc2 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -36,7 +46,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h index 38d729a0dc..0493af75e8 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/default_collisions_widget.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Dave Coleman */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h index 9b06c567fe..a080097be7 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -36,7 +46,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h index 9fb384f92a..56b8500aca 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/end_effectors_widget.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Dave Coleman */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h index dcac0b5af7..0f1c1a8cdd 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_edit_widget.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Dave Coleman */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h index 8c867806c7..c9b2ca1583 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/group_meta_config.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -36,7 +46,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h index d1b29f72f5..99c29f127c 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/kinematic_chain_widget.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Dave Coleman */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h index a434a9b87e..5167d2b36e 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -36,7 +46,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h index cacdf58b5b..3226c84d32 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/passive_joints_widget.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Dave Coleman */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h index efa9026e5c..437e8d162b 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -36,7 +46,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h index fcf3d4ec24..a1b06c2967 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/planning_groups_widget.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Dave Coleman */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h index e49cf96a4a..7e8cfd8d4a 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -36,7 +46,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h index 068f96bb82..f5e360af89 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/robot_poses_widget.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Dave Coleman */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h index aafbb0d401..cd9bfe3479 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/rotated_header_view.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Robert Haschke */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h index 102efa868b..f765ad4778 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/srdf_step.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -36,7 +46,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h index ecfbcecd0b..4ae077923b 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -36,7 +46,5 @@ /* Author: David V. Lu!! */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include diff --git a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h index ada6542a5f..1a00e505b2 100644 --- a/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h +++ b/moveit_setup_assistant/moveit_setup_srdf_plugins/include/moveit_setup_srdf_plugins/virtual_joints_widget.h @@ -1,5 +1,15 @@ -/* This file was autogenerated by create_deprecated_headers.py */ +/********************************************************************* + * All MoveIt 2 headers have been updated to use the .hpp extension. + * + * .h headers are now autogenerated via create_deprecated_headers.py, + * and will import the corresponding .hpp with a deprecation warning. + * + * imports via .h files may be removed in future releases, so please + * modify your imports to use the corresponding .hpp imports. + * + * See https://github.com/moveit/moveit2/pull/3113 for extra details. + *********************************************************************/ /********************************************************************* * Software License Agreement (BSD License) * @@ -37,7 +47,5 @@ /* Author: Dave Coleman */ #pragma once - #pragma message(".h header is obsolete. Please use the .hpp header instead.") - #include