diff --git a/include/moveit_task_constructor/storage.h b/include/moveit_task_constructor/storage.h index cdb28931..206ccc72 100644 --- a/include/moveit_task_constructor/storage.h +++ b/include/moveit_task_constructor/storage.h @@ -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; }; -} +} } diff --git a/include/moveit_task_constructor/subtask.h b/include/moveit_task_constructor/subtask.h index c4fd2ecd..0067470c 100644 --- a/include/moveit_task_constructor/subtask.h +++ b/include/moveit_task_constructor/subtask.h @@ -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 SubTaskWeakPtr; @@ -80,4 +80,4 @@ protected: std::pair< std::list::iterator, std::list::iterator > it_pairs_; }; -} +} } diff --git a/include/moveit_task_constructor/subtasks/cartesian_position_motion.h b/include/moveit_task_constructor/subtasks/cartesian_position_motion.h index 87b7c87f..9e435d6a 100644 --- a/include/moveit_task_constructor/subtasks/cartesian_position_motion.h +++ b/include/moveit_task_constructor/subtasks/cartesian_position_motion.h @@ -9,11 +9,11 @@ #include #include -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); }; -} +} } } diff --git a/include/moveit_task_constructor/subtasks/current_state.h b/include/moveit_task_constructor/subtasks/current_state.h index d84ec31e..587fa066 100644 --- a/include/moveit_task_constructor/subtasks/current_state.h +++ b/include/moveit_task_constructor/subtasks/current_state.h @@ -4,7 +4,7 @@ #include -namespace moveit::task_constructor::subtasks { +namespace moveit { namespace task_constructor { namespace subtasks { class CurrentState : public SubTask { public: @@ -18,4 +18,4 @@ protected: bool ran_; }; -} +} } } diff --git a/include/moveit_task_constructor/subtasks/generate_grasp_pose.h b/include/moveit_task_constructor/subtasks/generate_grasp_pose.h index 61d43b61..e0b6c60a 100644 --- a/include/moveit_task_constructor/subtasks/generate_grasp_pose.h +++ b/include/moveit_task_constructor/subtasks/generate_grasp_pose.h @@ -8,11 +8,11 @@ #include -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; }; -} +} } } diff --git a/include/moveit_task_constructor/subtasks/gripper.h b/include/moveit_task_constructor/subtasks/gripper.h index d715cf5c..c09d35a5 100644 --- a/include/moveit_task_constructor/subtasks/gripper.h +++ b/include/moveit_task_constructor/subtasks/gripper.h @@ -4,11 +4,11 @@ #include -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_; }; -} +} } } diff --git a/include/moveit_task_constructor/subtasks/move.h b/include/moveit_task_constructor/subtasks/move.h index ba4404ca..8e7da46d 100644 --- a/include/moveit_task_constructor/subtasks/move.h +++ b/include/moveit_task_constructor/subtasks/move.h @@ -4,11 +4,11 @@ #include -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_; }; -} +} } } diff --git a/include/moveit_task_constructor/task.h b/include/moveit_task_constructor/task.h index 1e0f46e7..77e1e74c 100644 --- a/include/moveit_task_constructor/task.h +++ b/include/moveit_task_constructor/task.h @@ -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; }; -} +} }