Fix clang-tidy warnings

This commit is contained in:
Robert Haschke 2022-11-02 12:25:03 +01:00
parent 7ff2f70b66
commit 7d5f9fe6e3
9 changed files with 26 additions and 25 deletions

View File

@ -48,7 +48,7 @@ namespace stages {
class FixedState : public Generator class FixedState : public Generator
{ {
public: public:
FixedState(const std::string& name = "initial state", planning_scene::PlanningScenePtr = nullptr); FixedState(const std::string& name = "initial state", planning_scene::PlanningScenePtr scene = nullptr);
void setState(const planning_scene::PlanningScenePtr& scene); void setState(const planning_scene::PlanningScenePtr& scene);
void reset() override; void reset() override;

View File

@ -248,7 +248,7 @@ private:
std::ostream& operator<<(std::ostream& os, const InterfaceState::Priority& prio); std::ostream& operator<<(std::ostream& os, const InterfaceState::Priority& prio);
std::ostream& operator<<(std::ostream& os, const Interface& interface); std::ostream& operator<<(std::ostream& os, const Interface& interface);
std::ostream& operator<<(std::ostream& os, Interface::Direction); std::ostream& operator<<(std::ostream& os, Interface::Direction dir);
/// Find index of the iterator in the container. Counting starts at 1. Zero corresponds to not found. /// Find index of the iterator in the container. Counting starts at 1. Zero corresponds to not found.
template <typename T> template <typename T>

View File

@ -125,8 +125,8 @@ StagePrivate& StagePrivate::operator=(StagePrivate&& other) {
prev_ends_ = std::move(other.prev_ends_); prev_ends_ = std::move(other.prev_ends_);
next_starts_ = std::move(other.next_starts_); next_starts_ = std::move(other.next_starts_);
parent_ = std::move(other.parent_); parent_ = other.parent_;
it_ = std::move(other.it_); it_ = other.it_;
other.unparent(); other.unparent();
return *this; return *this;

View File

@ -373,7 +373,7 @@ void ComputeIK::compute() {
req.max_contacts = 1; req.max_contacts = 1;
scene->checkCollision(req, res, *state); scene->checkCollision(req, res, *state);
solution.feasible = ignore_collisions || !res.collision; solution.feasible = ignore_collisions || !res.collision;
if (res.contacts.size() > 0) { if (!res.contacts.empty()) {
solution.contact = res.contacts.begin()->second.front(); solution.contact = res.contacts.begin()->second.front();
} }
return solution.feasible; return solution.feasible;

View File

@ -44,7 +44,7 @@ namespace task_constructor {
namespace stages { namespace stages {
FixedState::FixedState(const std::string& name, planning_scene::PlanningScenePtr scene) FixedState::FixedState(const std::string& name, planning_scene::PlanningScenePtr scene)
: Generator(name), scene_(scene) { : Generator(name), scene_(std::move(scene)) {
properties().declare("ignore_collisions", false); properties().declare("ignore_collisions", false);
setCostTerm(std::make_unique<cost::Constant>(0.0)); setCostTerm(std::make_unique<cost::Constant>(0.0));
} }

View File

@ -113,9 +113,9 @@ TEST_F(PandaMoveRelative, cartesianCircular) {
} }
TEST_F(PandaMoveRelative, cartesianRotateAttachedIKFrame) { TEST_F(PandaMoveRelative, cartesianRotateAttachedIKFrame) {
const std::string ATTACHED_OBJECT{ "attached_object" }; const std::string attached_object{ "attached_object" };
scene->processAttachedCollisionObjectMsg(createAttachedObject(ATTACHED_OBJECT)); scene->processAttachedCollisionObjectMsg(createAttachedObject(attached_object));
move->setIKFrame(ATTACHED_OBJECT); move->setIKFrame(attached_object);
move->setDirection([] { move->setDirection([] {
geometry_msgs::TwistStamped twist; geometry_msgs::TwistStamped twist;
@ -125,7 +125,7 @@ TEST_F(PandaMoveRelative, cartesianRotateAttachedIKFrame) {
}()); }());
ASSERT_TRUE(t.plan()) << "Failed to plan"; ASSERT_TRUE(t.plan()) << "Failed to plan";
EXPECT_CONST_POSITION(move->solutions().front(), ATTACHED_OBJECT); EXPECT_CONST_POSITION(move->solutions().front(), attached_object);
} }
int main(int argc, char** argv) { int main(int argc, char** argv) {

View File

@ -72,7 +72,8 @@ TEST_F(PandaMoveTo, stateTarget) {
EXPECT_ONE_SOLUTION; EXPECT_ONE_SOLUTION;
} }
geometry_msgs::PoseStamped getFramePoseOfNamedState(RobotState state, std::string pose, std::string frame) { geometry_msgs::PoseStamped getFramePoseOfNamedState(RobotState state, const std::string& pose,
const std::string& frame) {
state.setToDefaultValues(state.getRobotModel()->getJointModelGroup("panda_arm"), pose); state.setToDefaultValues(state.getRobotModel()->getJointModelGroup("panda_arm"), pose);
auto frame_eigen{ state.getFrameTransform(frame) }; auto frame_eigen{ state.getFrameTransform(frame) };
geometry_msgs::PoseStamped p; geometry_msgs::PoseStamped p;
@ -98,9 +99,9 @@ TEST_F(PandaMoveTo, poseTarget) {
} }
TEST_F(PandaMoveTo, poseIKFrameLinkTarget) { TEST_F(PandaMoveTo, poseIKFrameLinkTarget) {
const std::string IK_FRAME{ "panda_hand" }; const std::string ik_frame{ "panda_hand" };
move_to->setIKFrame(IK_FRAME); move_to->setIKFrame(ik_frame);
move_to->setGoal(getFramePoseOfNamedState(scene->getCurrentState(), "ready", IK_FRAME)); move_to->setGoal(getFramePoseOfNamedState(scene->getCurrentState(), "ready", ik_frame));
EXPECT_ONE_SOLUTION; EXPECT_ONE_SOLUTION;
} }
@ -129,22 +130,22 @@ moveit_msgs::AttachedCollisionObject createAttachedObject(const std::string& id)
} }
TEST_F(PandaMoveTo, poseIKFrameAttachedTarget) { TEST_F(PandaMoveTo, poseIKFrameAttachedTarget) {
const std::string ATTACHED_OBJECT{ "attached_object" }; const std::string attached_object{ "attached_object" };
scene->processAttachedCollisionObjectMsg(createAttachedObject(ATTACHED_OBJECT)); scene->processAttachedCollisionObjectMsg(createAttachedObject(attached_object));
move_to->setIKFrame(ATTACHED_OBJECT); move_to->setIKFrame(attached_object);
move_to->setGoal(getFramePoseOfNamedState(scene->getCurrentState(), "ready", ATTACHED_OBJECT)); move_to->setGoal(getFramePoseOfNamedState(scene->getCurrentState(), "ready", attached_object));
EXPECT_ONE_SOLUTION; EXPECT_ONE_SOLUTION;
} }
TEST_F(PandaMoveTo, poseIKFrameAttachedSubframeTarget) { TEST_F(PandaMoveTo, poseIKFrameAttachedSubframeTarget) {
const std::string ATTACHED_OBJECT{ "attached_object" }; const std::string attached_object{ "attached_object" };
const std::string IK_FRAME{ ATTACHED_OBJECT + "/subframe" }; const std::string ik_frame{ attached_object + "/subframe" };
scene->processAttachedCollisionObjectMsg(createAttachedObject(ATTACHED_OBJECT)); scene->processAttachedCollisionObjectMsg(createAttachedObject(attached_object));
move_to->setIKFrame(IK_FRAME); move_to->setIKFrame(ik_frame);
move_to->setGoal(getFramePoseOfNamedState(scene->getCurrentState(), "ready", IK_FRAME)); move_to->setGoal(getFramePoseOfNamedState(scene->getCurrentState(), "ready", ik_frame));
EXPECT_ONE_SOLUTION; EXPECT_ONE_SOLUTION;
} }

View File

@ -19,7 +19,7 @@ struct StandaloneGeneratorMockup : public GeneratorMockup
InterfacePtr next; InterfacePtr next;
StandaloneGeneratorMockup(std::initializer_list<double>&& costs) StandaloneGeneratorMockup(std::initializer_list<double>&& costs)
: StandaloneGeneratorMockup{ PredefinedCosts{ std::move(costs), true } } {} : StandaloneGeneratorMockup{ PredefinedCosts{ costs, true } } {}
StandaloneGeneratorMockup(PredefinedCosts&& costs = PredefinedCosts{ { 0.0 }, true }) StandaloneGeneratorMockup(PredefinedCosts&& costs = PredefinedCosts{ { 0.0 }, true })
: GeneratorMockup{ std::move(costs) } { : GeneratorMockup{ std::move(costs) } {

View File

@ -172,7 +172,7 @@ TaskPanelPrivate::TaskPanelPrivate(TaskPanel* panel) : q_ptr(panel) {
tool_buttons_group = new QButtonGroup(panel); tool_buttons_group = new QButtonGroup(panel);
tool_buttons_group->setExclusive(true); tool_buttons_group->setExclusive(true);
button_show_stage_dock_widget->setEnabled(bool(getStageFactory())); button_show_stage_dock_widget->setEnabled(bool(getStageFactory()));
button_show_stage_dock_widget->setToolTip(QStringLiteral("Show available stages")); button_show_stage_dock_widget->setToolTip("Show available stages");
property_root = new rviz::Property("Global Settings"); property_root = new rviz::Property("Global Settings");
} }