clang-tidy: llvm-namespace-comment

This commit is contained in:
v4hn 2020-06-10 13:09:06 +02:00
parent 2153237643
commit 8faba159f9
87 changed files with 190 additions and 189 deletions

View File

@ -1,5 +1,6 @@
--- ---
Checks: '-*, Checks: '-*,
llvm-namespace-comment,
modernize-use-nullptr, modernize-use-nullptr,
modernize-use-override, modernize-use-override,
modernize-use-using, modernize-use-using,

View File

@ -76,7 +76,7 @@ const moveit::core::JointModelGroup* findJointModelGroup(const moveit::core::Rob
return nullptr; return nullptr;
} }
} } // namespace
namespace move_group { namespace move_group {

View File

@ -227,5 +227,5 @@ public:
protected: protected:
WrapperBase(WrapperBasePrivate* impl, Stage::pointer&& child = Stage::pointer()); WrapperBase(WrapperBasePrivate* impl, Stage::pointer&& child = Stage::pointer());
}; };
} } // namespace task_constructor
} } // namespace moveit

View File

@ -264,5 +264,5 @@ public:
void sendBackward(SubTrajectory&& t, const InterfaceState* to); void sendBackward(SubTrajectory&& t, const InterfaceState* to);
}; };
PIMPL_FUNCTIONS(Merger) PIMPL_FUNCTIONS(Merger)
} } // namespace task_constructor
} } // namespace moveit

View File

@ -112,5 +112,5 @@ private:
/// retrieve solution with given id /// retrieve solution with given id
const SolutionBase* solutionFromId(uint id) const; const SolutionBase* solutionFromId(uint id) const;
}; };
} } // namespace task_constructor
} } // namespace moveit

View File

@ -43,5 +43,5 @@ void generateVisualMarkers(const moveit::core::RobotState& robot_state, const Ma
/** generate marker msgs to visualize the planning scene, calling the given callback for each of them /** generate marker msgs to visualize the planning scene, calling the given callback for each of them
* calls generateMarkersForRobot() and generateMarkersForObjects() */ * calls generateMarkersForRobot() and generateMarkersForObjects() */
void generateMarkersForScene(const planning_scene::PlanningSceneConstPtr& scene, const MarkerCallback& callback); void generateMarkersForScene(const planning_scene::PlanningSceneConstPtr& scene, const MarkerCallback& callback);
} } // namespace task_constructor
} } // namespace moveit

View File

@ -58,5 +58,5 @@ moveit::core::JointModelGroup* merge(const std::vector<const moveit::core::Joint
robot_trajectory::RobotTrajectoryPtr robot_trajectory::RobotTrajectoryPtr
merge(const std::vector<robot_trajectory::RobotTrajectoryConstPtr>& sub_trajectories, merge(const std::vector<robot_trajectory::RobotTrajectoryConstPtr>& sub_trajectories,
const moveit::core::RobotState& base_state, moveit::core::JointModelGroup*& merged_group); const moveit::core::RobotState& base_state, moveit::core::JointModelGroup*& merged_group);
} } // namespace task_constructor
} } // namespace moveit

View File

@ -70,6 +70,6 @@ public:
robot_trajectory::RobotTrajectoryPtr& result, robot_trajectory::RobotTrajectoryPtr& result,
const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints()) override; const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints()) override;
}; };
} } // namespace solvers
} } // namespace task_constructor
} } // namespace moveit

View File

@ -64,6 +64,6 @@ public:
robot_trajectory::RobotTrajectoryPtr& result, robot_trajectory::RobotTrajectoryPtr& result,
const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints()) override; const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints()) override;
}; };
} } // namespace solvers
} } // namespace task_constructor
} } // namespace moveit

View File

@ -75,6 +75,6 @@ public:
protected: protected:
planning_pipeline::PlanningPipelinePtr planner_; planning_pipeline::PlanningPipelinePtr planner_;
}; };
} } // namespace solvers
} } // namespace task_constructor
} } // namespace moveit

View File

@ -90,6 +90,6 @@ public:
robot_trajectory::RobotTrajectoryPtr& result, robot_trajectory::RobotTrajectoryPtr& result,
const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints()) = 0; const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints()) = 0;
}; };
} } // namespace solvers
} } // namespace task_constructor
} } // namespace moveit

View File

@ -385,5 +385,5 @@ protected:
/** Return (horizontal) flow symbol for start or end interface (specified by mask) */ /** Return (horizontal) flow symbol for start or end interface (specified by mask) */
template <unsigned int mask> template <unsigned int mask>
const char* flowSymbol(InterfaceFlags f); const char* flowSymbol(InterfaceFlags f);
} } // namespace task_constructor
} } // namespace moveit

View File

@ -113,6 +113,6 @@ public:
protected: protected:
ordered<const SolutionBase*> upstream_solutions_; ordered<const SolutionBase*> upstream_solutions_;
}; };
} } // namespace stages
} } // namespace task_constructor
} } // namespace moveit

View File

@ -98,6 +98,6 @@ protected:
std::list<SubTrajectory> subsolutions_; std::list<SubTrajectory> subsolutions_;
std::list<InterfaceState> states_; std::list<InterfaceState> states_;
}; };
} } // namespace stages
} } // namespace task_constructor
} } // namespace moveit

View File

@ -59,6 +59,6 @@ protected:
moveit::core::RobotModelConstPtr robot_model_; moveit::core::RobotModelConstPtr robot_model_;
planning_scene::PlanningScenePtr scene_; planning_scene::PlanningScenePtr scene_;
}; };
} } // namespace stages
} } // namespace task_constructor
} } // namespace moveit

View File

@ -61,6 +61,6 @@ public:
private: private:
SubTrajectory fixCollisions(planning_scene::PlanningScene& scene) const; SubTrajectory fixCollisions(planning_scene::PlanningScene& scene) const;
}; };
} } // namespace stages
} } // namespace task_constructor
} } // namespace moveit

View File

@ -61,6 +61,6 @@ protected:
void onNewSolution(const SolutionBase& s) override; void onNewSolution(const SolutionBase& s) override;
ordered<const SolutionBase*> upstream_solutions_; ordered<const SolutionBase*> upstream_solutions_;
}; };
} } // namespace stages
} } // namespace task_constructor
} } // namespace moveit

View File

@ -59,6 +59,6 @@ protected:
planning_scene::PlanningScenePtr scene_; planning_scene::PlanningScenePtr scene_;
bool ran_ = false; bool ran_ = false;
}; };
} } // namespace stages
} } // namespace task_constructor
} } // namespace moveit

View File

@ -64,6 +64,6 @@ public:
protected: protected:
void onNewSolution(const SolutionBase& s) override; void onNewSolution(const SolutionBase& s) override;
}; };
} } // namespace stages
} } // namespace task_constructor
} } // namespace moveit

View File

@ -60,6 +60,6 @@ public:
protected: protected:
void onNewSolution(const SolutionBase& s) override; void onNewSolution(const SolutionBase& s) override;
}; };
} } // namespace stages
} } // namespace task_constructor
} } // namespace moveit

View File

@ -61,6 +61,6 @@ protected:
void onNewSolution(const SolutionBase& s) override; void onNewSolution(const SolutionBase& s) override;
ordered<const SolutionBase*> upstream_solutions_; ordered<const SolutionBase*> upstream_solutions_;
}; };
} } // namespace stages
} } // namespace task_constructor
} } // namespace moveit

View File

@ -163,6 +163,6 @@ inline void ModifyPlanningScene::attachObject(const std::string& object, const s
inline void ModifyPlanningScene::detachObject(const std::string& object, const std::string& link) { inline void ModifyPlanningScene::detachObject(const std::string& object, const std::string& link) {
attachObjects(Names({ object }), link, false); attachObjects(Names({ object }), link, false);
} }
} } // namespace stages
} } // namespace task_constructor
} } // namespace moveit

View File

@ -103,6 +103,6 @@ protected:
protected: protected:
solvers::PlannerInterfacePtr planner_; solvers::PlannerInterfacePtr planner_;
}; };
} } // namespace stages
} } // namespace task_constructor
} } // namespace moveit

View File

@ -109,6 +109,6 @@ protected:
protected: protected:
solvers::PlannerInterfacePtr planner_; solvers::PlannerInterfacePtr planner_;
}; };
} } // namespace stages
} } // namespace task_constructor
} } // namespace moveit

View File

@ -121,6 +121,6 @@ public:
} }
void setPlaceMotion(const std::map<std::string, double>& joints) { setLiftPlace(joints); } void setPlaceMotion(const std::map<std::string, double>& joints) { setLiftPlace(joints); }
}; };
} } // namespace stages
} } // namespace task_constructor
} } // namespace moveit

View File

@ -66,6 +66,6 @@ public:
void setPredicate(const Predicate& p) { setProperty("predicate", p); } void setPredicate(const Predicate& p) { setProperty("predicate", p); }
}; };
} } // namespace stages
} } // namespace task_constructor
} } // namespace moveit

View File

@ -104,6 +104,6 @@ class SimpleUnGrasp : public SimpleGraspBase
public: public:
SimpleUnGrasp(Stage::pointer&& generator = Stage::pointer(), const std::string& name = "ungrasp"); SimpleUnGrasp(Stage::pointer&& generator = Stage::pointer(), const std::string& name = "ungrasp");
}; };
} } // namespace stages
} } // namespace task_constructor
} } // namespace moveit

View File

@ -318,8 +318,8 @@ template <>
inline const InterfaceState::Solutions& SolutionBase::trajectories<Interface::BACKWARD>() const { inline const InterfaceState::Solutions& SolutionBase::trajectories<Interface::BACKWARD>() const {
return start_->incomingTrajectories(); return start_->incomingTrajectories();
} }
} } // namespace task_constructor
} } // namespace moveit
namespace std { namespace std {
// comparison for pointers to SolutionBase: compare based on value // comparison for pointers to SolutionBase: compare based on value

View File

@ -158,5 +158,5 @@ inline std::ostream& operator<<(std::ostream& os, const Task& task) {
task.printState(os); task.printState(os);
return os; return os;
} }
} } // namespace task_constructor
} } // namespace moveit

View File

@ -71,5 +71,5 @@ private:
std::list<Task::TaskCallback> task_cbs_; // functions to monitor task's planning progress std::list<Task::TaskCallback> task_cbs_; // functions to monitor task's planning progress
}; };
PIMPL_FUNCTIONS(Task) PIMPL_FUNCTIONS(Task)
} } // namespace task_constructor
} } // namespace moveit

View File

@ -58,5 +58,5 @@ struct is_container<
decltype(std::declval<T>().cend())>, decltype(std::declval<T>().cend())>,
void> > : public std::true_type void> > : public std::true_type
{}; {};
} } // namespace task_constructor
} } // namespace moveit

View File

@ -959,5 +959,5 @@ void MergerPrivate::merge(const ChildSolutionList& sub_solutions,
t.setCost(costs); t.setCost(costs);
spawner(std::move(t)); spawner(std::move(t));
} }
} } // namespace task_constructor
} } // namespace moveit

View File

@ -258,5 +258,5 @@ Introspection::fillTaskStatistics(moveit_task_constructor_msgs::TaskStatistics&
msg.process_id = impl->process_id_; msg.process_id = impl->process_id_;
return msg; return msg;
} }
} } // namespace task_constructor
} } // namespace moveit

View File

@ -163,5 +163,5 @@ void generateMarkersForScene(const planning_scene::PlanningSceneConstPtr& scene,
generateMarkers<urdf::VisualSharedPtr>(scene->getCurrentState(), callback); generateMarkers<urdf::VisualSharedPtr>(scene->getCurrentState(), callback);
generateMarkersForObjects(scene, callback); generateMarkersForObjects(scene, callback);
} }
} } // namespace task_constructor
} } // namespace moveit

View File

@ -60,7 +60,7 @@ findDuplicates(const std::vector<const moveit::core::JointModelGroup*>& groups,
} }
return duplicates; return duplicates;
} }
} } // namespace
namespace moveit { namespace moveit {
namespace task_constructor { namespace task_constructor {
@ -171,5 +171,5 @@ merge(const std::vector<robot_trajectory::RobotTrajectoryConstPtr>& sub_trajecto
timing.computeTimeStamps(*merged_traj, 1.0, 1.0); timing.computeTimeStamps(*merged_traj, 1.0, 1.0);
return merged_traj; return merged_traj;
} }
} } // namespace task_constructor
} } // namespace moveit

View File

@ -112,6 +112,6 @@ bool CartesianPath::plan(const planning_scene::PlanningSceneConstPtr& from, cons
return achieved_fraction >= props.get<double>("min_fraction"); return achieved_fraction >= props.get<double>("min_fraction");
} }
} } // namespace solvers
} } // namespace task_constructor
} } // namespace moveit

View File

@ -102,6 +102,6 @@ bool JointInterpolationPlanner::plan(const planning_scene::PlanningSceneConstPtr
const moveit_msgs::Constraints& path_constraints) { const moveit_msgs::Constraints& path_constraints) {
throw std::runtime_error("Not yet implemented"); throw std::runtime_error("Not yet implemented");
} }
} } // namespace solvers
} } // namespace task_constructor
} } // namespace moveit

View File

@ -138,6 +138,6 @@ bool PipelinePlanner::plan(const planning_scene::PlanningSceneConstPtr& from, co
result = res.trajectory_; result = res.trajectory_;
return success; return success;
} }
} } // namespace solvers
} } // namespace task_constructor
} } // namespace moveit

View File

@ -49,4 +49,4 @@ PlannerInterface::PlannerInterface() {
} }
} }
} }
} } // namespace moveit

View File

@ -750,5 +750,5 @@ std::ostream& operator<<(std::ostream& os, const Stage& stage) {
os << *stage.pimpl(); os << *stage.pimpl();
return os; return os;
} }
} } // namespace task_constructor
} } // namespace moveit

View File

@ -431,6 +431,6 @@ void ComputeIK::compute() {
spawn(InterfaceState(scene), std::move(solution)); spawn(InterfaceState(scene), std::move(solution));
} }
} }
} } // namespace stages
} } // namespace task_constructor
} } // namespace moveit

View File

@ -244,6 +244,6 @@ SubTrajectoryPtr Connect::merge(const std::vector<robot_trajectory::RobotTraject
return std::make_shared<SubTrajectory>(trajectory, cost); return std::make_shared<SubTrajectory>(trajectory, cost);
} }
} } // namespace stages
} } // namespace task_constructor
} } // namespace moveit

View File

@ -93,9 +93,9 @@ void CurrentState::compute() {
} }
ROS_WARN("failed to acquire current PlanningScene"); ROS_WARN("failed to acquire current PlanningScene");
} }
} } // namespace stages
} } // namespace task_constructor
} } // namespace moveit
/// register plugin /// register plugin
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>

View File

@ -152,6 +152,6 @@ SubTrajectory FixCollisionObjects::fixCollisions(planning_scene::PlanningScene&
result.markAsFailure(); result.markAsFailure();
return result; return result;
} }
} } // namespace stages
} } // namespace task_constructor
} } // namespace moveit

View File

@ -97,6 +97,6 @@ void FixedCartesianPoses::compute() {
spawn(std::move(state), std::move(trajectory)); spawn(std::move(state), std::move(trajectory));
} }
} }
} } // namespace stages
} } // namespace task_constructor
} } // namespace moveit

View File

@ -60,6 +60,6 @@ void FixedState::compute() {
spawn(InterfaceState(scene_), 0.0); spawn(InterfaceState(scene_), 0.0);
ran_ = true; ran_ = true;
} }
} } // namespace stages
} } // namespace task_constructor
} } // namespace moveit

View File

@ -149,6 +149,6 @@ void GenerateGraspPose::compute() {
spawn(std::move(state), std::move(trajectory)); spawn(std::move(state), std::move(trajectory));
} }
} }
} } // namespace stages
} } // namespace task_constructor
} } // namespace moveit

View File

@ -159,6 +159,6 @@ void GeneratePlacePose::compute() {
// any other case: only try given target pose // any other case: only try given target pose
spawner(target_pose, 1, 1); spawner(target_pose, 1, 1);
} }
} } // namespace stages
} } // namespace task_constructor
} } // namespace moveit

View File

@ -86,6 +86,6 @@ void GeneratePose::compute() {
spawn(std::move(state), std::move(trajectory)); spawn(std::move(state), std::move(trajectory));
} }
} } // namespace stages
} } // namespace task_constructor
} } // namespace moveit

View File

@ -140,6 +140,6 @@ void ModifyPlanningScene::processCollisionObject(planning_scene::PlanningScene&
const moveit_msgs::CollisionObject& object) { const moveit_msgs::CollisionObject& object) {
scene.processCollisionObjectMsg(object); scene.processCollisionObjectMsg(object);
} }
} } // namespace stages
} } // namespace task_constructor
} } // namespace moveit

View File

@ -323,6 +323,6 @@ void MoveRelative::computeBackward(const InterfaceState& to) {
else else
silentFailure(); silentFailure();
} }
} } // namespace stages
} } // namespace task_constructor
} } // namespace moveit

View File

@ -274,6 +274,6 @@ void MoveTo::computeBackward(const InterfaceState& to) {
else else
silentFailure(); silentFailure();
} }
} } // namespace stages
} } // namespace task_constructor
} } // namespace moveit

View File

@ -98,6 +98,6 @@ void PickPlaceBase::setLiftPlace(const std::map<std::string, double>& joints) {
auto& p = lift_stage_->properties(); auto& p = lift_stage_->properties();
p.set("joints", joints); p.set("joints", joints);
} }
} } // namespace stages
} } // namespace task_constructor
} } // namespace moveit

View File

@ -88,6 +88,6 @@ void PredicateFilter::onNewSolution(const SolutionBase& s) {
liftSolution(s, cost, comment); liftSolution(s, cost, comment);
} }
} } // namespace stages
} } // namespace task_constructor
} } // namespace moveit

View File

@ -156,6 +156,6 @@ SimpleGrasp::SimpleGrasp(std::unique_ptr<Stage>&& generator, const std::string&
SimpleUnGrasp::SimpleUnGrasp(std::unique_ptr<Stage>&& generator, const std::string& name) : SimpleGraspBase(name) { SimpleUnGrasp::SimpleUnGrasp(std::unique_ptr<Stage>&& generator, const std::string& name) : SimpleGraspBase(name) {
setup(std::move(generator), false); setup(std::move(generator), false);
} }
} } // namespace stages
} } // namespace task_constructor
} } // namespace moveit

View File

@ -201,5 +201,5 @@ void SolutionSequence::fillMessage(moveit_task_constructor_msgs::Solution& msg,
} }
} }
} }
} } // namespace task_constructor
} } // namespace moveit

View File

@ -66,7 +66,7 @@ std::string rosNormalizeName(const std::string& name) {
} }
return n; return n;
} }
} } // namespace
namespace moveit { namespace moveit {
namespace task_constructor { namespace task_constructor {
@ -364,5 +364,5 @@ const core::RobotModelConstPtr& Task::getRobotModel() const {
void Task::printState(std::ostream& os) const { void Task::printState(std::ostream& os) const {
os << *stages(); os << *stages();
} }
} } // namespace task_constructor
} } // namespace moveit

View File

@ -175,7 +175,7 @@ const std::string S_MODEL0 =
"</group>" "</group>"
"<end_effector name=\"eef\" parent_link=\"link_b\" group=\"mim_joints\" parent_group=\"base_from_base_to_tip\"/>" "<end_effector name=\"eef\" parent_link=\"link_b\" group=\"mim_joints\" parent_group=\"base_from_base_to_tip\"/>"
"</robot>"; "</robot>";
} } // namespace
RobotModelPtr getModel() { RobotModelPtr getModel() {
urdf::ModelInterfaceSharedPtr urdf_model = urdf::parseURDF(R_MODEL0); urdf::ModelInterfaceSharedPtr urdf_model = urdf::parseURDF(R_MODEL0);

View File

@ -121,4 +121,4 @@ private:
geometry_msgs::Pose place_pose_; geometry_msgs::Pose place_pose_;
double place_surface_offset_; double place_surface_offset_;
}; };
} // moveit_task_constructor_demo } // namespace moveit_task_constructor_demo

View File

@ -449,4 +449,4 @@ bool PickPlaceTask::execute() {
return true; return true;
} }
} } // namespace moveit_task_constructor_demo

View File

@ -164,4 +164,4 @@ rviz::Property* PropertyFactory::createDefault(const std::string& name, const st
} }
} }
#endif #endif
} } // namespace moveit_rviz_plugin

View File

@ -128,4 +128,4 @@ private:
void registerType(const std::string& type_name, const PropertyFactoryFunction& f); void registerType(const std::string& type_name, const PropertyFactoryFunction& f);
void registerStage(const std::type_index& type_index, const TreeFactoryFunction& f); void registerStage(const std::type_index& type_index, const TreeFactoryFunction& f);
}; };
} } // namespace moveit_rviz_plugin

View File

@ -291,7 +291,7 @@ rviz::Property* Parser::processSequence(const QString& name, const QString& desc
root->removeChildren(index, root->numChildren() - index); root->removeChildren(index, root->numChildren() - index);
return root; return root;
} }
} } // namespace
namespace moveit_rviz_plugin { namespace moveit_rviz_plugin {
@ -303,4 +303,4 @@ rviz::Property* PropertyFactory::createDefault(const std::string& name, const st
Parser parser(value); Parser parser(value);
return parser.process(qname, qdesc, old); return parser.process(qname, qdesc, old);
} }
} } // namespace moveit_rviz_plugin

View File

@ -91,4 +91,4 @@ QMimeData* FactoryModel::mimeData(const QModelIndexList& indexes) const {
} }
return mime_data; return mime_data;
} }
} } // namespace moveit_rviz_plugin

View File

@ -55,4 +55,4 @@ public:
QStringList mimeTypes() const override; QStringList mimeTypes() const override;
QMimeData* mimeData(const QModelIndexList& indexes) const override; QMimeData* mimeData(const QModelIndexList& indexes) const override;
}; };
} } // namespace moveit_rviz_plugin

View File

@ -77,5 +77,5 @@ void JobQueue::executeJobs() {
} }
idle_condition_.notify_all(); idle_condition_.notify_all();
} }
} } // namespace tools
} } // namespace moveit

View File

@ -63,5 +63,5 @@ public:
void waitForAllJobs(); void waitForAllJobs();
void executeJobs(); void executeJobs();
}; };
} } // namespace tools
} } // namespace moveit

View File

@ -245,4 +245,4 @@ rviz::PropertyTreeModel* LocalTaskModel::getPropertyModel(const QModelIndex& ind
} }
return it_inserted.first->second; return it_inserted.first->second;
} }
} } // namespace moveit_rviz_plugin

View File

@ -78,4 +78,4 @@ public:
rviz::PropertyTreeModel* getPropertyModel(const QModelIndex& index) override; rviz::PropertyTreeModel* getPropertyModel(const QModelIndex& index) override;
}; };
} } // namespace moveit_rviz_plugin

View File

@ -118,4 +118,4 @@ std::pair<BaseTaskModel*, QModelIndex> MetaTaskListModel::getTaskModel(const QMo
Q_ASSERT(dynamic_cast<BaseTaskModel*>(m.first)); Q_ASSERT(dynamic_cast<BaseTaskModel*>(m.first));
return std::make_pair(static_cast<BaseTaskModel*>(m.first), m.second); return std::make_pair(static_cast<BaseTaskModel*>(m.first), m.second);
} }
} } // namespace moveit_rviz_plugin

View File

@ -88,4 +88,4 @@ public:
/// retrieve TaskModel and its source index corresponding to given proxy index /// retrieve TaskModel and its source index corresponding to given proxy index
std::pair<BaseTaskModel*, QModelIndex> getTaskModel(const QModelIndex& index) const; std::pair<BaseTaskModel*, QModelIndex> getTaskModel(const QModelIndex& index) const;
}; };
} } // namespace moveit_rviz_plugin

View File

@ -189,4 +189,4 @@ private:
pluginlib::ClassLoader<Type>* class_loader_; pluginlib::ClassLoader<Type>* class_loader_;
QHash<QString, BuiltInClassRecord> built_ins_; QHash<QString, BuiltInClassRecord> built_ins_;
}; };
} } // namespace moveit_rviz_plugin

View File

@ -470,7 +470,7 @@ typename T::iterator insert(T& c, typename T::value_type&& item) {
else else
return p.first; return p.first;
} }
} } // namespace detail
RemoteSolutionModel::RemoteSolutionModel(QObject* parent) : QAbstractTableModel(parent) {} RemoteSolutionModel::RemoteSolutionModel(QObject* parent) : QAbstractTableModel(parent) {}
@ -660,4 +660,4 @@ void RemoteSolutionModel::processSolutionIDs(const std::vector<uint32_t>& ids, b
bool RemoteSolutionModel::isVisible(const RemoteSolutionModel::Data& item) const { bool RemoteSolutionModel::isVisible(const RemoteSolutionModel::Data& item) const {
return std::isnan(item.cost) || item.cost <= max_cost_; return std::isnan(item.cost) || item.cost <= max_cost_;
} }
} } // namespace moveit_rviz_plugin

View File

@ -147,4 +147,4 @@ public:
void processSolutionIDs(const std::vector<uint32_t>& successful, const std::vector<uint32_t>& failed, void processSolutionIDs(const std::vector<uint32_t>& successful, const std::vector<uint32_t>& failed,
size_t num_failed, double total_compute_time); size_t num_failed, double total_compute_time);
}; };
} } // namespace moveit_rviz_plugin

View File

@ -460,6 +460,6 @@ void TaskListView::dropEvent(QDropEvent* event) {
if (event->isAccepted()) if (event->isAccepted())
expand(index); expand(index);
} }
} } // namespace moveit_rviz_plugin
#include "moc_task_list_model.cpp" #include "moc_task_list_model.cpp"

View File

@ -208,4 +208,4 @@ public:
void dropEvent(QDropEvent* event) override; void dropEvent(QDropEvent* event) override;
}; };
} } // namespace moveit_rviz_plugin

View File

@ -498,6 +498,6 @@ void GlobalSettingsWidget::save(rviz::Config config) {
void GlobalSettingsWidget::load(const rviz::Config& config) { void GlobalSettingsWidget::load(const rviz::Config& config) {
d_ptr->properties->getRoot()->load(config); d_ptr->properties->getRoot()->load(config);
} }
} } // namespace moveit_rviz_plugin
#include "moc_task_panel.cpp" #include "moc_task_panel.cpp"

View File

@ -157,4 +157,4 @@ public:
void save(rviz::Config config) override; void save(rviz::Config config) override;
void load(const rviz::Config& config) override; void load(const rviz::Config& config) override;
}; };
} } // namespace moveit_rviz_plugin

View File

@ -94,4 +94,4 @@ public:
GlobalSettingsWidget* q_ptr; GlobalSettingsWidget* q_ptr;
rviz::PropertyTreeModel* properties; rviz::PropertyTreeModel* properties;
}; };
} } // namespace moveit_rviz_plugin

View File

@ -598,7 +598,7 @@ void FlatMergeProxyModelPrivate::_q_sourceDataChanged(const QModelIndex& topLeft
q_ptr->dataChanged(mapFromSource(topLeft), mapFromSource(bottomRight)); q_ptr->dataChanged(mapFromSource(topLeft), mapFromSource(bottomRight));
} }
#endif #endif
} } // namespace utils
} } // namespace moveit_rviz_plugin
#include "moc_flat_merge_proxy_model.cpp" #include "moc_flat_merge_proxy_model.cpp"

View File

@ -117,5 +117,5 @@ private:
Q_PRIVATE_SLOT(d_func(), void _q_sourceDataChanged(QModelIndex, QModelIndex)) Q_PRIVATE_SLOT(d_func(), void _q_sourceDataChanged(QModelIndex, QModelIndex))
#endif #endif
}; };
} } // namespace utils
} } // namespace moveit_rviz_plugin

View File

@ -212,5 +212,5 @@ QIcon Icon::combinedIcon(const QList<QIcon>& icons) {
result.addPixmap(icon.pixmap(window, size, mode), mode); result.addPixmap(icon.pixmap(window, size, mode), mode);
return result; return result;
} }
} } // namespace utils
} } // namespace moveit_rviz_plugin

View File

@ -81,7 +81,7 @@ public:
private: private:
IconStyleOptions m_style = NONE; IconStyleOptions m_style = NONE;
}; };
} } // namespace utils
} } // namespace moveit_rviz_plugin
Q_DECLARE_OPERATORS_FOR_FLAGS(moveit_rviz_plugin::utils::Icon::IconStyleOptions) Q_DECLARE_OPERATORS_FOR_FLAGS(moveit_rviz_plugin::utils::Icon::IconStyleOptions)

View File

@ -570,7 +570,7 @@ void TreeMergeProxyModelPrivate::_q_sourceDataChanged(const QModelIndex& topLeft
q_ptr->dataChanged(mapFromSource(topLeft), mapFromSource(bottomRight)); q_ptr->dataChanged(mapFromSource(topLeft), mapFromSource(bottomRight));
} }
#endif #endif
} } // namespace utils
} } // namespace moveit_rviz_plugin
#include "moc_tree_merge_proxy_model.cpp" #include "moc_tree_merge_proxy_model.cpp"

View File

@ -117,5 +117,5 @@ private:
Q_PRIVATE_SLOT(d_func(), void _q_sourceDataChanged(QModelIndex, QModelIndex)) Q_PRIVATE_SLOT(d_func(), void _q_sourceDataChanged(QModelIndex, QModelIndex))
#endif #endif
}; };
} } // namespace utils
} } // namespace moveit_rviz_plugin

View File

@ -128,4 +128,4 @@ public:
const moveit_task_constructor_msgs::Solution& msg); const moveit_task_constructor_msgs::Solution& msg);
void fillMessage(moveit_task_constructor_msgs::Solution& msg) const; void fillMessage(moveit_task_constructor_msgs::Solution& msg) const;
}; };
} } // namespace moveit_rviz_plugin

View File

@ -61,7 +61,7 @@ class EnumProperty;
class EditableEnumProperty; class EditableEnumProperty;
class ColorProperty; class ColorProperty;
class PanelDockWidget; class PanelDockWidget;
} } // namespace rviz
namespace moveit { namespace moveit {
namespace core { namespace core {