mirror of
https://github.com/moveit/moveit_task_constructor.git
synced 2025-11-04 14:49:57 +08:00
avoid shortened nested namespace definitions
`namespace X::Y { }` is only part of the C++17 standard.
I did not notice before because GCC 6+ do not warn about
this even with `-pedantic -std=c++14`.
This commit is contained in:
parent
557b1cbe16
commit
2dfc2f395e
@ -15,7 +15,7 @@ namespace robot_trajectory {
|
||||
MOVEIT_CLASS_FORWARD(RobotTrajectory);
|
||||
}
|
||||
|
||||
namespace moveit::task_constructor {
|
||||
namespace moveit { namespace task_constructor {
|
||||
|
||||
MOVEIT_CLASS_FORWARD(SubTrajectory);
|
||||
MOVEIT_CLASS_FORWARD(InterfaceState);
|
||||
@ -63,4 +63,4 @@ struct SubTrajectory {
|
||||
bool flag;
|
||||
};
|
||||
|
||||
}
|
||||
} }
|
||||
|
||||
@ -19,7 +19,7 @@ namespace planning_pipeline {
|
||||
MOVEIT_CLASS_FORWARD(PlanningPipeline);
|
||||
}
|
||||
|
||||
namespace moveit::task_constructor {
|
||||
namespace moveit { namespace task_constructor {
|
||||
|
||||
MOVEIT_CLASS_FORWARD(SubTask);
|
||||
typedef std::weak_ptr<SubTask> SubTaskWeakPtr;
|
||||
@ -80,4 +80,4 @@ protected:
|
||||
std::pair< std::list<InterfaceState>::iterator, std::list<InterfaceState>::iterator > it_pairs_;
|
||||
};
|
||||
|
||||
}
|
||||
} }
|
||||
|
||||
@ -9,11 +9,11 @@
|
||||
#include <geometry_msgs/Vector3Stamped.h>
|
||||
#include <geometry_msgs/PointStamped.h>
|
||||
|
||||
namespace moveit::planning_interface {
|
||||
namespace moveit { namespace planning_interface {
|
||||
MOVEIT_CLASS_FORWARD(MoveGroupInterface);
|
||||
}
|
||||
} }
|
||||
|
||||
namespace moveit::task_constructor::subtasks {
|
||||
namespace moveit { namespace task_constructor { namespace subtasks {
|
||||
|
||||
class CartesianPositionMotion : public SubTask {
|
||||
public:
|
||||
@ -60,4 +60,4 @@ protected:
|
||||
void _publishTrajectory(const robot_trajectory::RobotTrajectory& trajectory, const moveit::core::RobotState& start);
|
||||
};
|
||||
|
||||
}
|
||||
} } }
|
||||
|
||||
@ -4,7 +4,7 @@
|
||||
|
||||
#include <moveit_task_constructor/subtask.h>
|
||||
|
||||
namespace moveit::task_constructor::subtasks {
|
||||
namespace moveit { namespace task_constructor { namespace subtasks {
|
||||
|
||||
class CurrentState : public SubTask {
|
||||
public:
|
||||
@ -18,4 +18,4 @@ protected:
|
||||
bool ran_;
|
||||
};
|
||||
|
||||
}
|
||||
} } }
|
||||
|
||||
@ -8,11 +8,11 @@
|
||||
|
||||
#include <moveit/macros/class_forward.h>
|
||||
|
||||
namespace moveit::planning_interface {
|
||||
namespace moveit { namespace planning_interface {
|
||||
MOVEIT_CLASS_FORWARD(MoveGroupInterface);
|
||||
}
|
||||
} }
|
||||
|
||||
namespace moveit::task_constructor::subtasks {
|
||||
namespace moveit { namespace task_constructor { namespace subtasks {
|
||||
|
||||
class GenerateGraspPose : public SubTask {
|
||||
public:
|
||||
@ -76,4 +76,4 @@ protected:
|
||||
ros::Publisher pub;
|
||||
};
|
||||
|
||||
}
|
||||
} } }
|
||||
|
||||
@ -4,11 +4,11 @@
|
||||
|
||||
#include <moveit_task_constructor/subtask.h>
|
||||
|
||||
namespace moveit::planning_interface {
|
||||
namespace moveit { namespace planning_interface {
|
||||
MOVEIT_CLASS_FORWARD(MoveGroupInterface);
|
||||
}
|
||||
} }
|
||||
|
||||
namespace moveit::task_constructor::subtasks {
|
||||
namespace moveit { namespace task_constructor { namespace subtasks {
|
||||
|
||||
class Gripper : public SubTask {
|
||||
public:
|
||||
@ -40,4 +40,4 @@ protected:
|
||||
std::string attach_link_;
|
||||
};
|
||||
|
||||
}
|
||||
} } }
|
||||
|
||||
@ -4,11 +4,11 @@
|
||||
|
||||
#include <moveit_task_constructor/subtask.h>
|
||||
|
||||
namespace moveit::planning_interface {
|
||||
namespace moveit { namespace planning_interface {
|
||||
MOVEIT_CLASS_FORWARD(MoveGroupInterface);
|
||||
}
|
||||
} }
|
||||
|
||||
namespace moveit::task_constructor::subtasks {
|
||||
namespace moveit { namespace task_constructor { namespace subtasks {
|
||||
|
||||
class Move : public SubTask {
|
||||
public:
|
||||
@ -41,4 +41,4 @@ protected:
|
||||
moveit::planning_interface::MoveGroupInterfacePtr mgi_;
|
||||
};
|
||||
|
||||
}
|
||||
} } }
|
||||
|
||||
@ -26,7 +26,7 @@ namespace robot_trajectory {
|
||||
MOVEIT_CLASS_FORWARD(RobotTrajectory);
|
||||
}
|
||||
|
||||
namespace moveit::task_constructor {
|
||||
namespace moveit { namespace task_constructor {
|
||||
|
||||
MOVEIT_CLASS_FORWARD(SubTask);
|
||||
|
||||
@ -63,4 +63,4 @@ protected:
|
||||
ros::Publisher pub;
|
||||
};
|
||||
|
||||
}
|
||||
} }
|
||||
|
||||
Loading…
Reference in New Issue
Block a user