diff --git a/.github/workflows/ci.yaml b/.github/workflows/ci.yaml index 470c517158f..c475a94885a 100644 --- a/.github/workflows/ci.yaml +++ b/.github/workflows/ci.yaml @@ -40,13 +40,13 @@ jobs: BEFORE_BUILD_UPSTREAM_WORKSPACE: ccache -z AFTER_BUILD_TARGET_WORKSPACE: ccache -s # Changing linker to lld as ld has a behavior where it takes a long time to finish - # Compile CCOV with Debug. Enable -Werror (except CLANG_TIDY=pedantic, which makes the clang-tidy step fail on warnings) + # Compile CCOV with Debug. Enable -Werror. TARGET_CMAKE_ARGS: > -DCMAKE_EXE_LINKER_FLAGS=-fuse-ld=lld -DCMAKE_SHARED_LINKER_FLAGS=-fuse-ld=lld -DCMAKE_MODULE_LINKER_FLAGS=-fuse-ld=lld -DCMAKE_BUILD_TYPE=${{ matrix.env.CCOV && 'Debug' || 'Release'}} - -DCMAKE_CXX_FLAGS="${{ matrix.env.CLANG_TIDY != 'pedantic' && '-Werror ' || '' }}$CXXFLAGS${{ matrix.env.CCOV && ' --coverage -O2 -fno-omit-frame-pointer'}}" + -DCMAKE_CXX_FLAGS="-Werror $CXXFLAGS${{ matrix.env.CCOV && ' --coverage -O2 -fno-omit-frame-pointer'}}" UPSTREAM_CMAKE_ARGS: "-DCMAKE_CXX_FLAGS=''" DOWNSTREAM_CMAKE_ARGS: -DCMAKE_CXX_FLAGS="-Wall -Wextra" CCACHE_DIR: ${{ github.workspace }}/.ccache 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 18ea04470cf..1192ff87f6f 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 @@ -96,6 +96,9 @@ class AllowedCollisionMatrix /** @brief Copy constructor */ AllowedCollisionMatrix(const AllowedCollisionMatrix& acm) = default; + /** @brief Copy assignment */ + AllowedCollisionMatrix& operator=(const AllowedCollisionMatrix&) = default; + /** @brief Get the type of the allowed collision between two elements. * Return true if the entry is included in the collision matrix. Return false if the entry is not found. * @param name1 name of first element 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 571ba980816..36567bf365e 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 @@ -354,9 +354,9 @@ TYPED_TEST_P(DistanceFullPandaTest, DistancePoints) } } -REGISTER_TYPED_TEST_CASE_P(CollisionDetectorPandaTest, InitOK, DefaultNotInCollision, LinksInCollision, - RobotWorldCollision_1, RobotWorldCollision_2, PaddingTest, DistanceSelf, DistanceWorld); +REGISTER_TYPED_TEST_SUITE_P(CollisionDetectorPandaTest, InitOK, DefaultNotInCollision, LinksInCollision, + RobotWorldCollision_1, RobotWorldCollision_2, PaddingTest, DistanceSelf, DistanceWorld); -REGISTER_TYPED_TEST_CASE_P(DistanceCheckPandaTest, DistanceSingle); +REGISTER_TYPED_TEST_SUITE_P(DistanceCheckPandaTest, DistanceSingle); -REGISTER_TYPED_TEST_CASE_P(DistanceFullPandaTest, DistancePoints); +REGISTER_TYPED_TEST_SUITE_P(DistanceFullPandaTest, DistancePoints); 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 b3c3f003744..db9ba733d9c 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 @@ -564,6 +564,6 @@ TYPED_TEST_P(CollisionDetectorTest, TestChangingShapeSize) } } -REGISTER_TYPED_TEST_CASE_P(CollisionDetectorTest, InitOK, DefaultNotInCollision, LinksInCollision, ContactReporting, - ContactPositions, AttachedBodyTester, DiffSceneTester, ConvertObjectToAttached, - TestCollisionMapAdditionSpeed, MoveMesh, TestChangingShapeSize); +REGISTER_TYPED_TEST_SUITE_P(CollisionDetectorTest, InitOK, DefaultNotInCollision, LinksInCollision, ContactReporting, + ContactPositions, AttachedBodyTester, DiffSceneTester, ConvertObjectToAttached, + TestCollisionMapAdditionSpeed, MoveMesh, TestChangingShapeSize); 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 339cd15c3b1..1e164b33f7b 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 @@ -37,8 +37,14 @@ #include #include -INSTANTIATE_TYPED_TEST_CASE_P(BulletCollisionCheckPanda, CollisionDetectorPandaTest, - collision_detection::CollisionDetectorAllocatorBullet); +INSTANTIATE_TYPED_TEST_SUITE_P(BulletCollisionCheckPanda, CollisionDetectorPandaTest, + collision_detection::CollisionDetectorAllocatorBullet); + +// These are not instantiated, because be don't yet have distance checking for Bullet +#ifdef GTEST_ALLOW_UNINSTANTIATED_PARAMETERIZED_TEST +GTEST_ALLOW_UNINSTANTIATED_PARAMETERIZED_TEST(DistanceCheckPandaTest); +GTEST_ALLOW_UNINSTANTIATED_PARAMETERIZED_TEST(DistanceFullPandaTest); +#endif int main(int argc, char* argv[]) { 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 e522c6d67e3..997d73b689b 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 @@ -37,8 +37,8 @@ #include #include -INSTANTIATE_TYPED_TEST_CASE_P(BulletCollisionCheck, CollisionDetectorTest, - collision_detection::CollisionDetectorAllocatorBullet); +INSTANTIATE_TYPED_TEST_SUITE_P(BulletCollisionCheck, CollisionDetectorTest, + collision_detection::CollisionDetectorAllocatorBullet); int main(int argc, char* argv[]) { 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 d6c810ab880..78aa8732b87 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 @@ -37,19 +37,25 @@ #include #include -INSTANTIATE_TYPED_TEST_CASE_P(FCLCollisionCheckPanda, CollisionDetectorPandaTest, - collision_detection::CollisionDetectorAllocatorFCL); +INSTANTIATE_TYPED_TEST_SUITE_P(FCLCollisionCheckPanda, CollisionDetectorPandaTest, + collision_detection::CollisionDetectorAllocatorFCL); // FCL < 0.6 incorrectly reports distance results in the object coordinate frame. // See: https://github.com/flexible-collision-library/fcl/issues/171 // and https://github.com/flexible-collision-library/fcl/pull/288. // So only execute the full distance test suite on FCL >= 0.6. #if MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0) -INSTANTIATE_TYPED_TEST_CASE_P(FCLDistanceCheckPanda, DistanceFullPandaTest, - collision_detection::CollisionDetectorAllocatorFCL); +INSTANTIATE_TYPED_TEST_SUITE_P(FCLDistanceCheckPanda, DistanceFullPandaTest, + collision_detection::CollisionDetectorAllocatorFCL); +#ifdef GTEST_ALLOW_UNINSTANTIATED_PARAMETERIZED_TEST +GTEST_ALLOW_UNINSTANTIATED_PARAMETERIZED_TEST(DistanceCheckPandaTest); +#endif #else -INSTANTIATE_TYPED_TEST_CASE_P(FCLDistanceCheckPanda, DistanceCheckPandaTest, - collision_detection::CollisionDetectorAllocatorFCL); +INSTANTIATE_TYPED_TEST_SUITE_P(FCLDistanceCheckPanda, DistanceCheckPandaTest, + collision_detection::CollisionDetectorAllocatorFCL); +#ifdef GTEST_ALLOW_UNINSTANTIATED_PARAMETERIZED_TEST +GTEST_ALLOW_UNINSTANTIATED_PARAMETERIZED_TEST(DistanceFullPandaTest); +#endif #endif int main(int argc, char* argv[]) 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 efe312cf3bb..6818fb13a94 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 @@ -37,8 +37,8 @@ #include #include -INSTANTIATE_TYPED_TEST_CASE_P(FCLCollisionCheck, CollisionDetectorTest, - collision_detection::CollisionDetectorAllocatorFCL); +INSTANTIATE_TYPED_TEST_SUITE_P(FCLCollisionCheck, CollisionDetectorTest, + collision_detection::CollisionDetectorAllocatorFCL); int main(int argc, char* argv[]) { diff --git a/moveit_core/robot_state/src/robot_state.cpp b/moveit_core/robot_state/src/robot_state.cpp index 7cd29e3f156..91810f6f0e0 100644 --- a/moveit_core/robot_state/src/robot_state.cpp +++ b/moveit_core/robot_state/src/robot_state.cpp @@ -1605,8 +1605,9 @@ bool RobotState::setFromIK(const JointModelGroup* jmg, const EigenSTL::vector_Is std::string error_msg; if (!solver->supportsGroup(jmg, &error_msg)) { - RCLCPP_ERROR(LOGGER, "Kinematics solver %s does not support joint group %s. Error: %s", typeid(*solver).name(), - jmg->getName().c_str(), error_msg.c_str()); + const kinematics::KinematicsBase& solver_ref = *solver; + RCLCPP_ERROR(LOGGER, "Kinematics solver %s does not support joint group %s. Error: %s", + typeid(solver_ref).name(), jmg->getName().c_str(), error_msg.c_str()); valid_solver = false; } } 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 4746e119670..98d362dd258 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 @@ -11,6 +11,11 @@ MOVEIT_CLASS_FORWARD(TimeParameterization); class TimeParameterization { public: + TimeParameterization() = default; + TimeParameterization(const TimeParameterization&) = default; + TimeParameterization(TimeParameterization&&) = default; + TimeParameterization& operator=(const TimeParameterization&) = default; + TimeParameterization& operator=(TimeParameterization&&) = default; virtual ~TimeParameterization() = default; virtual bool computeTimeStamps(robot_trajectory::RobotTrajectory& trajectory, const double max_velocity_scaling_factor = 1.0, 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 b1120c38647..3746696e9a2 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 @@ -57,7 +57,10 @@ class GreedyKCenters using Matrix = Eigen::MatrixXd; GreedyKCenters() = default; - + GreedyKCenters(const GreedyKCenters&) = default; + GreedyKCenters(GreedyKCenters&&) noexcept = default; + GreedyKCenters& operator=(const GreedyKCenters&) = default; + GreedyKCenters& operator=(GreedyKCenters&&) noexcept = default; virtual ~GreedyKCenters() = default; /** \brief Set the distance function to use */ 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 0cdeb250b52..359dfe51577 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 @@ -52,7 +52,10 @@ class NearestNeighbors typedef std::function DistanceFunction; NearestNeighbors() = default; - + NearestNeighbors(const NearestNeighbors&) = default; + NearestNeighbors(NearestNeighbors&&) noexcept = default; + NearestNeighbors& operator=(const NearestNeighbors&) = default; + NearestNeighbors& operator=(NearestNeighbors&&) noexcept = default; virtual ~NearestNeighbors() = default; /** \brief Set the distance function to use */ 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 bd8f7cdb234..42166ffb35b 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 @@ -44,10 +44,11 @@ template class BaseCmd : public MotionCmd { public: - BaseCmd() : MotionCmd() - { - } - + BaseCmd() = default; + BaseCmd(const BaseCmd&) = default; + BaseCmd(BaseCmd&&) noexcept = default; + BaseCmd& operator=(const BaseCmd&) = default; + BaseCmd& operator=(BaseCmd&&) noexcept = default; virtual ~BaseCmd() = default; public: 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 620d2fe4681..dd4a03d07dd 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 @@ -48,6 +48,12 @@ namespace pilz_industrial_motion_planner_testutils class GoalConstraintMsgConvertible { public: + GoalConstraintMsgConvertible() = default; + GoalConstraintMsgConvertible(const GoalConstraintMsgConvertible&) = default; + GoalConstraintMsgConvertible(GoalConstraintMsgConvertible&&) = default; + GoalConstraintMsgConvertible& operator=(const GoalConstraintMsgConvertible&) = default; + GoalConstraintMsgConvertible& operator=(GoalConstraintMsgConvertible&&) = default; + virtual ~GoalConstraintMsgConvertible() = default; virtual moveit_msgs::msg::Constraints toGoalConstraints() const = 0; }; } // 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 7fb3fe7e874..7e9da57924f 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 @@ -46,6 +46,12 @@ namespace pilz_industrial_motion_planner_testutils class RobotStateMsgConvertible { public: + RobotStateMsgConvertible() = default; + RobotStateMsgConvertible(const RobotStateMsgConvertible&) = default; + RobotStateMsgConvertible(RobotStateMsgConvertible&&) = default; + RobotStateMsgConvertible& operator=(const RobotStateMsgConvertible&) = default; + RobotStateMsgConvertible& operator=(RobotStateMsgConvertible&&) = default; + virtual ~RobotStateMsgConvertible() = default; virtual moveit_msgs::msg::RobotState toMoveitMsgsRobotState() const = 0; }; } // 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 19099ba0e74..10ea232571e 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 @@ -60,6 +60,10 @@ class TestdataLoader { } + TestdataLoader(const TestdataLoader&) = default; + TestdataLoader(TestdataLoader&&) = default; + TestdataLoader& operator=(const TestdataLoader&) = default; + TestdataLoader& operator=(TestdataLoader&&) = default; virtual ~TestdataLoader() = default; public: 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 810f3c468c8..c523df53d1e 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 @@ -184,8 +184,14 @@ class XmlTestdataLoader : public TestdataLoader class AbstractCmdGetterAdapter { public: - virtual CmdVariant getCmd(const std::string& /*cmd_name*/) const = 0; + AbstractCmdGetterAdapter() = default; + AbstractCmdGetterAdapter(const AbstractCmdGetterAdapter&) = default; + AbstractCmdGetterAdapter(AbstractCmdGetterAdapter&&) = default; + AbstractCmdGetterAdapter& operator=(const AbstractCmdGetterAdapter&) = default; + AbstractCmdGetterAdapter& operator=(AbstractCmdGetterAdapter&&) = default; virtual ~AbstractCmdGetterAdapter() = default; + + virtual CmdVariant getCmd(const std::string& /*cmd_name*/) const = 0; }; private: diff --git a/moveit_planners/trajopt/include/trajopt_interface/problem_description.h b/moveit_planners/trajopt/include/trajopt_interface/problem_description.h index 3a84346eee5..c8a8598856f 100644 --- a/moveit_planners/trajopt/include/trajopt_interface/problem_description.h +++ b/moveit_planners/trajopt/include/trajopt_interface/problem_description.h @@ -144,6 +144,11 @@ struct TermInfo using MakerFunc = TermInfoPtr (*)(void); static void RegisterMaker(const std::string& type, MakerFunc); + TermInfo() = default; + TermInfo(const TermInfo&) = default; + TermInfo(TermInfo&&) = default; + TermInfo& operator=(const TermInfo&) = default; + TermInfo& operator=(TermInfo&&) = default; virtual ~TermInfo() = default; protected: 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 8cef1260c19..7cfcafa96ad 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 @@ -55,6 +55,12 @@ namespace moveit::hybrid_planning class GlobalPlannerInterface { public: + GlobalPlannerInterface() = default; + GlobalPlannerInterface(const GlobalPlannerInterface&) = default; + GlobalPlannerInterface(GlobalPlannerInterface&&) = default; + GlobalPlannerInterface& operator=(const GlobalPlannerInterface&) = default; + GlobalPlannerInterface& operator=(GlobalPlannerInterface&&) = default; + virtual ~GlobalPlannerInterface() = default; /** * Initialize global planner * @return True if initialization was successful 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 0db65f68b22..a50afbef646 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 @@ -50,7 +50,7 @@ class MoveItPlanningPipeline : public GlobalPlannerInterface { public: MoveItPlanningPipeline() = default; - ~MoveItPlanningPipeline() = default; + ~MoveItPlanningPipeline() override = default; bool initialize(const rclcpp::Node::SharedPtr& node) override; bool reset() noexcept override; moveit_msgs::msg::MotionPlanResponse 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 d42a3eeae82..971b4858eb9 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 @@ -104,6 +104,13 @@ class HybridPlanningManager; // Forward declaration class PlannerLogicInterface { public: + PlannerLogicInterface() = default; + PlannerLogicInterface(const PlannerLogicInterface&) = default; + PlannerLogicInterface(PlannerLogicInterface&&) = default; + PlannerLogicInterface& operator=(const PlannerLogicInterface&) = default; + PlannerLogicInterface& operator=(PlannerLogicInterface&&) = default; + virtual ~PlannerLogicInterface() = default; + /** * Initialize the planner logic * @param hybrid_planning_manager The hybrid planning manager instance to initialize this logic with. 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 6ce0f65dc3a..7fd25903a8e 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 @@ -47,7 +47,7 @@ class ReplanInvalidatedTrajectory : public SinglePlanExecution // Inherit from { public: ReplanInvalidatedTrajectory() = default; - ~ReplanInvalidatedTrajectory() = default; + ~ReplanInvalidatedTrajectory() override = default; ReactionResult react(const std::string& event) override; }; } // 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 339631ef9d7..62b6e713a65 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 @@ -46,7 +46,7 @@ class SinglePlanExecution : public PlannerLogicInterface { public: SinglePlanExecution() = default; - ~SinglePlanExecution() = default; + ~SinglePlanExecution() override = default; bool initialize(const std::shared_ptr& hybrid_planning_manager) override; ReactionResult react(const HybridPlanningEvent& event) override; ReactionResult react(const std::string& event) override; 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 4685bb3f083..d63ddda28a1 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 @@ -49,7 +49,7 @@ class ForwardTrajectory : public LocalConstraintSolverInterface { public: ForwardTrajectory() = default; - ~ForwardTrajectory() = default; + ~ForwardTrajectory() override = default; bool initialize(const rclcpp::Node::SharedPtr& node, const planning_scene_monitor::PlanningSceneMonitorPtr& planning_scene_monitor, const std::string& /* unused */) override; 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 25ba1fda8d4..c3390be6225 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 @@ -59,6 +59,12 @@ namespace moveit::hybrid_planning class LocalConstraintSolverInterface { public: + LocalConstraintSolverInterface() = default; + LocalConstraintSolverInterface(const LocalConstraintSolverInterface&) = default; + LocalConstraintSolverInterface(LocalConstraintSolverInterface&&) = default; + LocalConstraintSolverInterface& operator=(const LocalConstraintSolverInterface&) = default; + LocalConstraintSolverInterface& operator=(LocalConstraintSolverInterface&&) = default; + virtual ~LocalConstraintSolverInterface() = default; /** * Initialize local constraint solver * @return True if initialization was successful 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 35ca5940c5d..f27c1c46508 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 @@ -60,6 +60,12 @@ namespace moveit::hybrid_planning class TrajectoryOperatorInterface { public: + TrajectoryOperatorInterface() = default; + TrajectoryOperatorInterface(const TrajectoryOperatorInterface&) = default; + TrajectoryOperatorInterface(TrajectoryOperatorInterface&&) = default; + TrajectoryOperatorInterface& operator=(const TrajectoryOperatorInterface&) = default; + TrajectoryOperatorInterface& operator=(TrajectoryOperatorInterface&&) = default; + virtual ~TrajectoryOperatorInterface() = default; /** * Initialize trajectory operator * @param node Node handle to access parameters 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 e462ed3b414..ed73e0221d0 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 @@ -47,7 +47,7 @@ class SimpleSampler : public TrajectoryOperatorInterface { public: SimpleSampler() = default; - ~SimpleSampler() = default; + ~SimpleSampler() override = default; bool initialize([[maybe_unused]] const rclcpp::Node::SharedPtr& node, const moveit::core::RobotModelConstPtr& robot_model, const std::string& group_name) override; diff --git a/moveit_ros/hybrid_planning/test/hybrid_planning_demo_node.cpp b/moveit_ros/hybrid_planning/test/hybrid_planning_demo_node.cpp index 5829956f754..92edd22f662 100644 --- a/moveit_ros/hybrid_planning/test/hybrid_planning_demo_node.cpp +++ b/moveit_ros/hybrid_planning/test/hybrid_planning_demo_node.cpp @@ -265,7 +265,7 @@ class HybridPlanningDemo send_goal_options.feedback_callback = [](const rclcpp_action::ClientGoalHandle::SharedPtr& /*unused*/, const std::shared_ptr& feedback) { - RCLCPP_INFO(LOGGER, feedback->feedback.c_str()); + RCLCPP_INFO_STREAM(LOGGER, feedback->feedback); }; RCLCPP_INFO(LOGGER, "Sending hybrid planning goal"); diff --git a/moveit_ros/moveit_servo/src/servo_calcs.cpp b/moveit_ros/moveit_servo/src/servo_calcs.cpp index cf21da4fa87..5e870816466 100644 --- a/moveit_ros/moveit_servo/src/servo_calcs.cpp +++ b/moveit_ros/moveit_servo/src/servo_calcs.cpp @@ -1258,10 +1258,10 @@ void ServoCalcs::twistStampedCB(const geometry_msgs::msg::TwistStamped::ConstSha { const std::lock_guard lock(main_loop_mutex_); latest_twist_stamped_ = msg; - latest_twist_cmd_is_nonzero_ = isNonZero(*latest_twist_stamped_.get()); + latest_twist_cmd_is_nonzero_ = isNonZero(*latest_twist_stamped_); - if (msg.get()->header.stamp != rclcpp::Time(0.)) - latest_twist_command_stamp_ = msg.get()->header.stamp; + if (msg->header.stamp != rclcpp::Time(0.)) + latest_twist_command_stamp_ = msg->header.stamp; // notify that we have a new input new_input_cmd_ = true; @@ -1272,10 +1272,10 @@ void ServoCalcs::jointCmdCB(const control_msgs::msg::JointJog::ConstSharedPtr& m { const std::lock_guard lock(main_loop_mutex_); latest_joint_cmd_ = msg; - latest_joint_cmd_is_nonzero_ = isNonZero(*latest_joint_cmd_.get()); + latest_joint_cmd_is_nonzero_ = isNonZero(*latest_joint_cmd_); - if (msg.get()->header.stamp != rclcpp::Time(0.)) - latest_joint_command_stamp_ = msg.get()->header.stamp; + if (msg->header.stamp != rclcpp::Time(0.)) + latest_joint_command_stamp_ = msg->header.stamp; // notify that we have a new input new_input_cmd_ = true; @@ -1284,7 +1284,7 @@ void ServoCalcs::jointCmdCB(const control_msgs::msg::JointJog::ConstSharedPtr& m void ServoCalcs::collisionVelocityScaleCB(const std_msgs::msg::Float64::ConstSharedPtr& msg) { - collision_velocity_scale_ = msg.get()->data; + collision_velocity_scale_ = msg->data; } void ServoCalcs::changeDriftDimensions(const std::shared_ptr& req, diff --git a/moveit_ros/moveit_servo/test/servo_launch_test_common.hpp b/moveit_ros/moveit_servo/test/servo_launch_test_common.hpp index 0b62b650be3..60dc70863b2 100644 --- a/moveit_ros/moveit_servo/test/servo_launch_test_common.hpp +++ b/moveit_ros/moveit_servo/test/servo_launch_test_common.hpp @@ -160,7 +160,7 @@ class ServoFixture : public ::testing::Test // Status sub (we need this to check that we've started / stopped) sub_servo_status_ = node_->create_subscription( resolveServoTopicName(servo_parameters_->status_topic), rclcpp::SystemDefaultsQoS(), - [this](const std_msgs::msg::Int8::SharedPtr msg) { return statusCB(msg); }); + [this](const std_msgs::msg::Int8::ConstSharedPtr& msg) { return statusCB(msg); }); return true; } @@ -234,7 +234,7 @@ class ServoFixture : public ::testing::Test { sub_collision_scale_ = node_->create_subscription( resolveServoTopicName("~/collision_velocity_scale"), rclcpp::SystemDefaultsQoS(), - [this](const std_msgs::msg::Float64::SharedPtr msg) { return collisionScaleCB(msg); }); + [this](const std_msgs::msg::Float64::ConstSharedPtr& msg) { return collisionScaleCB(msg); }); return true; } @@ -244,14 +244,14 @@ class ServoFixture : public ::testing::Test { sub_trajectory_cmd_output_ = node_->create_subscription( resolveServoTopicName(servo_parameters_->command_out_topic), rclcpp::SystemDefaultsQoS(), - [this](const trajectory_msgs::msg::JointTrajectory::SharedPtr msg) { return trajectoryCommandCB(msg); }); + [this](const trajectory_msgs::msg::JointTrajectory::ConstSharedPtr& msg) { return trajectoryCommandCB(msg); }); return true; } else if (command_type == "std_msgs/Float64MultiArray") { sub_array_cmd_output_ = node_->create_subscription( resolveServoTopicName(servo_parameters_->command_out_topic), rclcpp::SystemDefaultsQoS(), - [this](const std_msgs::msg::Float64MultiArray::SharedPtr msg) { return arrayCommandCB(msg); }); + [this](const std_msgs::msg::Float64MultiArray::ConstSharedPtr& msg) { return arrayCommandCB(msg); }); return true; } else @@ -269,20 +269,20 @@ class ServoFixture : public ::testing::Test return true; } - void statusCB(const std_msgs::msg::Int8::SharedPtr& msg) + void statusCB(const std_msgs::msg::Int8::ConstSharedPtr& msg) { const std::lock_guard lock(latest_state_mutex_); ++num_status_; - latest_status_ = static_cast(msg.get()->data); + latest_status_ = static_cast(msg->data); if (latest_status_ == status_tracking_code_) status_seen_ = true; } - void collisionScaleCB(const std_msgs::msg::Float64::SharedPtr& msg) + void collisionScaleCB(const std_msgs::msg::Float64::ConstSharedPtr& msg) { const std::lock_guard lock(latest_state_mutex_); ++num_collision_scale_; - latest_collision_scale_ = msg.get()->data; + latest_collision_scale_ = msg->data; } void jointStateCB(const sensor_msgs::msg::JointState::ConstSharedPtr& msg) @@ -292,14 +292,14 @@ class ServoFixture : public ::testing::Test latest_joint_state_ = msg; } - void trajectoryCommandCB(const trajectory_msgs::msg::JointTrajectory::SharedPtr& msg) + void trajectoryCommandCB(const trajectory_msgs::msg::JointTrajectory::ConstSharedPtr& msg) { const std::lock_guard lock(latest_state_mutex_); ++num_commands_; latest_traj_cmd_ = msg; } - void arrayCommandCB(const std_msgs::msg::Float64MultiArray::SharedPtr& msg) + void arrayCommandCB(const std_msgs::msg::Float64MultiArray::ConstSharedPtr& msg) { const std::lock_guard lock(latest_state_mutex_); ++num_commands_; @@ -488,7 +488,7 @@ class ServoFixture : public ::testing::Test sensor_msgs::msg::JointState::ConstSharedPtr latest_joint_state_; size_t num_commands_; - trajectory_msgs::msg::JointTrajectory::SharedPtr latest_traj_cmd_; + trajectory_msgs::msg::JointTrajectory::ConstSharedPtr latest_traj_cmd_; std_msgs::msg::Float64MultiArray::ConstSharedPtr latest_array_cmd_; bool status_seen_; diff --git a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.hpp b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.hpp index e3f64b6a944..947add0c933 100644 --- a/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.hpp +++ b/moveit_setup_assistant/moveit_setup_app_plugins/include/moveit_setup_app_plugins/perception_config.hpp @@ -72,7 +72,7 @@ class PerceptionConfig : public SetupConfig void setConfig(const SensorParameters& parameters); - class GeneratedSensorConfig : public YamlGeneratedFile + class GeneratedSensorConfig final : public YamlGeneratedFile { public: GeneratedSensorConfig(const std::filesystem::path& package_path, const GeneratedTime& last_gen_time, diff --git a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.hpp b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.hpp index 7fb608f23ed..662dbea5d1d 100644 --- a/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.hpp +++ b/moveit_setup_assistant/moveit_setup_controllers/include/moveit_setup_controllers/controllers.hpp @@ -54,6 +54,13 @@ class AdditionalControllerField { } + AdditionalControllerField() = default; + AdditionalControllerField(const AdditionalControllerField&) = default; + AdditionalControllerField(AdditionalControllerField&&) = default; + AdditionalControllerField& operator=(const AdditionalControllerField&) = default; + AdditionalControllerField& operator=(AdditionalControllerField&&) = default; + virtual ~AdditionalControllerField() = default; + /** * @brief Overridable method for changing the default value based on the controller_type */ 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 aef41b207e8..2188b3d6a37 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 @@ -57,6 +57,13 @@ MOVEIT_CLASS_FORWARD(SetupConfig); // Defines SetupConfigPtr, ConstPtr, WeakPtr class SetupConfig { public: + SetupConfig() = default; + SetupConfig(const SetupConfig&) = default; + SetupConfig(SetupConfig&&) = default; + SetupConfig& operator=(const SetupConfig&) = default; + SetupConfig& operator=(SetupConfig&&) = default; + virtual ~SetupConfig() = default; + /** * @brief Called after construction to initialize the step * @param config_data Pointer to all the other configs 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 0798d21297d..4f3288ead45 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 @@ -66,6 +66,10 @@ MOVEIT_CLASS_FORWARD(GeneratedFile); // Defines GeneratedFilePtr, ConstPtr, Wea class GeneratedFile : public std::enable_shared_from_this { public: + GeneratedFile(const GeneratedFile&) = default; + GeneratedFile(GeneratedFile&&) = default; + virtual ~GeneratedFile() = default; + GeneratedFile(const std::filesystem::path& package_path, const GeneratedTime& last_gen_time) : package_path_(package_path), last_gen_time_(last_gen_time) { diff --git a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.hpp b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.hpp index 79e05ca37f7..55594359bc4 100644 --- a/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.hpp +++ b/moveit_setup_assistant/moveit_setup_framework/include/moveit_setup_framework/setup_step.hpp @@ -46,6 +46,13 @@ namespace moveit_setup class SetupStep { public: + SetupStep() = default; + SetupStep(const SetupStep&) = default; + SetupStep(SetupStep&&) = default; + SetupStep& operator=(const SetupStep&) = default; + SetupStep& operator=(SetupStep&&) = default; + virtual ~SetupStep() = default; + /** * @brief Called after construction to initialize the step * @param parent_node Shared pointer to the parent node