diff --git a/.clang-tidy b/.clang-tidy index d74c8c8d..cdf9cd48 100644 --- a/.clang-tidy +++ b/.clang-tidy @@ -4,6 +4,7 @@ Checks: '-*, modernize-use-override, modernize-use-using, modernize-loop-convert, + readability-named-parameter, ' HeaderFilterRegex: '.*/moveit/task_constructor/.*\.h' AnalyzeTemporaryDtors: false diff --git a/capabilities/src/execute_task_solution_capability.cpp b/capabilities/src/execute_task_solution_capability.cpp index 42ae877b..99ebb677 100644 --- a/capabilities/src/execute_task_solution_capability.cpp +++ b/capabilities/src/execute_task_solution_capability.cpp @@ -166,7 +166,8 @@ bool ExecuteTaskSolutionCapability::constructMotionPlan(const moveit_task_constr exec_traj.trajectory_->setRobotTrajectoryMsg(state, sub_traj.trajectory); /* TODO add action feedback and markers */ - exec_traj.effect_on_success_ = [this, sub_traj, description](const plan_execution::ExecutableMotionPlan*) { + exec_traj.effect_on_success_ = [this, sub_traj, + description](const plan_execution::ExecutableMotionPlan* /*plan*/) { #if MOVEIT_MASTER if (!moveit::core::isEmpty(sub_traj.scene_diff)) { #else diff --git a/core/include/moveit/task_constructor/properties.h b/core/include/moveit/task_constructor/properties.h index a1380d7f..e96ed958 100644 --- a/core/include/moveit/task_constructor/properties.h +++ b/core/include/moveit/task_constructor/properties.h @@ -194,8 +194,8 @@ public: using SerializeFunction = std::string (*)(const boost::any&); using DeserializeFunction = boost::any (*)(const std::string&); - static std::string dummySerialize(const boost::any&) { return ""; } - static boost::any dummyDeserialize(const std::string&) { return boost::any(); } + static std::string dummySerialize(const boost::any& /*unused*/) { return ""; } + static boost::any dummyDeserialize(const std::string& /*unused*/) { return boost::any(); } protected: static bool insert(const std::type_index& type_index, const std::string& type_name, SerializeFunction serialize, diff --git a/core/include/moveit/task_constructor/stages/move_to.h b/core/include/moveit/task_constructor/stages/move_to.h index 68dacdcb..66613a14 100644 --- a/core/include/moveit/task_constructor/stages/move_to.h +++ b/core/include/moveit/task_constructor/stages/move_to.h @@ -104,7 +104,7 @@ protected: decltype(std::declval().markers()) & markers); bool getPointGoal(const boost::any& goal, const moveit::core::LinkModel* link, const planning_scene::PlanningScenePtr& scene, Eigen::Isometry3d& target_eigen, - decltype(std::declval().markers()) &); + decltype(std::declval().markers()) & /*unused*/); protected: solvers::PlannerInterfacePtr planner_; diff --git a/core/src/introspection.cpp b/core/src/introspection.cpp index a35cd1de..ed9649fc 100644 --- a/core/src/introspection.cpp +++ b/core/src/introspection.cpp @@ -204,7 +204,7 @@ void Introspection::fillStageStatistics(const Stage& stage, moveit_task_construc moveit_task_constructor_msgs::TaskDescription& Introspection::fillTaskDescription(moveit_task_constructor_msgs::TaskDescription& msg) { - ContainerBase::StageCallback stageProcessor = [this, &msg](const Stage& stage, unsigned int) -> bool { + ContainerBase::StageCallback stageProcessor = [this, &msg](const Stage& stage, unsigned int /*depth*/) -> bool { // this method is called for each child stage of a given parent moveit_task_constructor_msgs::StageDescription desc; desc.id = stageId(&stage); @@ -240,7 +240,7 @@ Introspection::fillTaskDescription(moveit_task_constructor_msgs::TaskDescription moveit_task_constructor_msgs::TaskStatistics& Introspection::fillTaskStatistics(moveit_task_constructor_msgs::TaskStatistics& msg) { - ContainerBase::StageCallback stageProcessor = [this, &msg](const Stage& stage, unsigned int) -> bool { + ContainerBase::StageCallback stageProcessor = [this, &msg](const Stage& stage, unsigned int /*depth*/) -> bool { // this method is called for each child stage of a given parent moveit_task_constructor_msgs::StageStatistics stat; // create new Stage msg stat.id = stageId(&stage); diff --git a/core/src/stages/move_to.cpp b/core/src/stages/move_to.cpp index 8034bdb0..556a774d 100644 --- a/core/src/stages/move_to.cpp +++ b/core/src/stages/move_to.cpp @@ -147,7 +147,7 @@ bool MoveTo::getPoseGoal(const boost::any& goal, const geometry_msgs::PoseStampe bool MoveTo::getPointGoal(const boost::any& goal, const moveit::core::LinkModel* link, const planning_scene::PlanningScenePtr& scene, Eigen::Isometry3d& target_eigen, - decltype(std::declval().markers()) &) { + decltype(std::declval().markers()) & /*unused*/) { try { const geometry_msgs::PointStamped& target = boost::any_cast(goal); Eigen::Vector3d target_point; @@ -160,6 +160,8 @@ bool MoveTo::getPointGoal(const boost::any& goal, const moveit::core::LinkModel* // retain link orientation target_eigen = scene->getCurrentState().getGlobalLinkTransform(link); target_eigen.translation() = target_point; + + // TODO: add marker visualization } catch (const boost::bad_any_cast&) { return false; } diff --git a/core/src/task.cpp b/core/src/task.cpp index ffa8b8ca..34703007 100644 --- a/core/src/task.cpp +++ b/core/src/task.cpp @@ -219,7 +219,7 @@ void Task::enableIntrospection(bool enable) { // reset introspection instance of all stages pimpl()->setIntrospection(nullptr); pimpl()->traverseStages( - [](Stage& stage, int) { + [](Stage& stage, int /*depth*/) { stage.pimpl()->setIntrospection(nullptr); return true; }, @@ -271,7 +271,7 @@ void Task::init() { // provide introspection instance to all stages impl->setIntrospection(impl->introspection_.get()); impl->traverseStages( - [impl](Stage& stage, int) { + [impl](Stage& stage, int /*depth*/) { stage.pimpl()->setIntrospection(impl->introspection_.get()); return true; }, diff --git a/core/test/test_container.cpp b/core/test/test_container.cpp index b5f7d2ae..dd70cc16 100644 --- a/core/test/test_container.cpp +++ b/core/test/test_container.cpp @@ -33,7 +33,7 @@ public: : MonitoringGenerator("monitoring generator " + std::to_string(++mock_id), monitored) {} bool canCompute() const override { return false; } void compute() override {} - void onNewSolution(const SolutionBase&) override {} + void onNewSolution(const SolutionBase& /*solution*/) override {} }; class PropagatorMockup : public PropagatingEitherWay diff --git a/visualization/motion_planning_tasks/properties/property_factory.cpp b/visualization/motion_planning_tasks/properties/property_factory.cpp index fddaa91f..6e8c1239 100644 --- a/visualization/motion_planning_tasks/properties/property_factory.cpp +++ b/visualization/motion_planning_tasks/properties/property_factory.cpp @@ -49,7 +49,8 @@ namespace mtc = ::moveit::task_constructor; namespace moveit_rviz_plugin { static rviz::StringProperty* stringFactory(const QString& name, mtc::Property& mtc_prop, - const planning_scene::PlanningScene*, rviz::DisplayContext*) { + const planning_scene::PlanningScene* /*unused*/, + rviz::DisplayContext* /*unused*/) { std::string value; if (!mtc_prop.value().empty()) value = boost::any_cast(mtc_prop.value()); @@ -61,7 +62,8 @@ static rviz::StringProperty* stringFactory(const QString& name, mtc::Property& m } template static rviz::FloatProperty* floatFactory(const QString& name, mtc::Property& mtc_prop, - const planning_scene::PlanningScene*, rviz::DisplayContext*) { + const planning_scene::PlanningScene* /*unused*/, + rviz::DisplayContext* /*unused*/) { T value = !mtc_prop.value().empty() ? boost::any_cast(mtc_prop.value()) : T(); rviz::FloatProperty* rviz_prop = new rviz::FloatProperty(name, value, QString::fromStdString(mtc_prop.description())); diff --git a/visualization/visualization_tools/include/moveit/visualization_tools/task_solution_visualization.h b/visualization/visualization_tools/include/moveit/visualization_tools/task_solution_visualization.h index 7b0996ca..fefe9f16 100644 --- a/visualization/visualization_tools/include/moveit/visualization_tools/task_solution_visualization.h +++ b/visualization/visualization_tools/include/moveit/visualization_tools/task_solution_visualization.h @@ -119,7 +119,7 @@ public Q_SLOTS: void interruptCurrentDisplay(); private Q_SLOTS: - void onAllAtOnceChanged(bool); + void onAllAtOnceChanged(bool all_at_once); // trajectory property slots void changedRobotVisualEnabled();