Skip to content

Commit

Permalink
Merge PR moveit#1712: fix clang compiler warnings + stricter CI
Browse files Browse the repository at this point in the history
  • Loading branch information
rhaschke authored Jan 26, 2023
2 parents b1e8b2d + 0dd9670 commit 936b4ad
Show file tree
Hide file tree
Showing 36 changed files with 168 additions and 59 deletions.
12 changes: 9 additions & 3 deletions .github/workflows/ci.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,10 @@ jobs:
ROS_DISTRO: rolling
IKFAST_TEST: true
CLANG_TIDY: pedantic
# Silent gmock/gtest warnings: https://github.com/ament/googletest/pull/21
AFTER_BUILD_UPSTREAM_WORKSPACE: |
git clone --quiet --branch clalancette/update-to-gtest-1.11 https://github.com/ament/googletest "${BASEDIR}/upstream_ws/src/googletest"
builder_run_build "/opt/ros/${ROS_DISTRO}" "${BASEDIR}/upstream_ws" --packages-select gtest_vendor gmock_vendor
- IMAGE: humble-ci
ROS_DISTRO: humble
- IMAGE: humble-ci-testing
Expand All @@ -32,7 +36,9 @@ jobs:
-Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls
CLANG_TIDY_ARGS: --fix --fix-errors --format-style=file
DOCKER_IMAGE: ghcr.io/ros-planning/moveit2:${{ matrix.env.IMAGE }}
UPSTREAM_WORKSPACE: moveit2.repos $(f="moveit2_$(sed 's/-.*$//' <<< "${{ matrix.env.IMAGE }}").repos"; test -r $f && echo $f)
UPSTREAM_WORKSPACE: >
moveit2.repos
$(f="moveit2_$(sed 's/-.*$//' <<< "${{ matrix.env.IMAGE }}").repos"; test -r $f && echo $f)
# Pull any updates to the upstream workspace (after restoring it from cache)
AFTER_SETUP_UPSTREAM_WORKSPACE: vcs pull $BASEDIR/upstream_ws/src
AFTER_SETUP_DOWNSTREAM_WORKSPACE: vcs pull $BASEDIR/downstream_ws/src
Expand All @@ -41,13 +47,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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -360,9 +360,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);
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,14 @@
#include <moveit/collision_detection_bullet/collision_detector_allocator_bullet.h>
#include <moveit/collision_detection/test_collision_common_panda.h>

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[])
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,8 @@
#include <moveit/collision_detection_bullet/collision_detector_allocator_bullet.h>
#include <moveit/collision_detection/test_collision_common_pr2.h>

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[])
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,19 +37,25 @@
#include <moveit/collision_detection_fcl/collision_detector_allocator_fcl.h>
#include <moveit/collision_detection/test_collision_common_panda.h>

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[])
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,8 @@
#include <moveit/collision_detection_fcl/collision_detector_allocator_fcl.h>
#include <moveit/collision_detection/test_collision_common_pr2.h>

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[])
{
Expand Down
5 changes: 3 additions & 2 deletions moveit_core/robot_state/src/robot_state.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1683,8 +1683,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;
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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 */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,10 @@ class NearestNeighbors
typedef std::function<double(const _T&, const _T&)> 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 */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -144,7 +144,7 @@ void TrajectoryGenerator::checkStartState(const moveit_msgs::msg::RobotState& st

// does not allow start velocity
if (!std::all_of(group_start_state.velocity.begin(), group_start_state.velocity.end(),
[this](double v) { return std::fabs(v) < VELOCITY_TOLERANCE; }))
[](double v) { return std::fabs(v) < VELOCITY_TOLERANCE; }))
{
throw NonZeroVelocityInStartState("Trajectory Generator does not allow non-zero start velocity");
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,10 +44,11 @@ template <class StartType, class GoalType>
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:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Original file line number Diff line number Diff line change
Expand Up @@ -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
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ class SinglePlanExecution : public PlannerLogicInterface
{
public:
SinglePlanExecution() = default;
~SinglePlanExecution() = default;
~SinglePlanExecution() override = default;
bool initialize(const std::shared_ptr<HybridPlanningManager>& hybrid_planning_manager) override;
ReactionResult react(const HybridPlanningEvent& event) override;
ReactionResult react(const std::string& event) override;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -265,7 +265,7 @@ class HybridPlanningDemo
send_goal_options.feedback_callback =
[](const rclcpp_action::ClientGoalHandle<moveit_msgs::action::HybridPlanner>::SharedPtr& /*unused*/,
const std::shared_ptr<const moveit_msgs::action::HybridPlanner::Feedback>& feedback) {
RCLCPP_INFO(LOGGER, feedback->feedback.c_str());
RCLCPP_INFO_STREAM(LOGGER, feedback->feedback);
};

RCLCPP_INFO(LOGGER, "Sending hybrid planning goal");
Expand Down
Loading

0 comments on commit 936b4ad

Please sign in to comment.