Add missing semicolons after cleanup of MoveIt

This commit is contained in:
Robert Haschke 2021-05-28 23:40:42 +02:00
parent dce740fdfe
commit 437cc550f2
25 changed files with 71 additions and 71 deletions

View File

@ -51,8 +51,8 @@
namespace moveit { namespace moveit {
namespace core { namespace core {
MOVEIT_CLASS_FORWARD(JointModelGroup) MOVEIT_CLASS_FORWARD(JointModelGroup);
MOVEIT_CLASS_FORWARD(RobotState) MOVEIT_CLASS_FORWARD(RobotState);
} // namespace core } // namespace core
} // namespace moveit } // namespace moveit

View File

@ -52,8 +52,8 @@
namespace moveit { namespace moveit {
namespace task_constructor { namespace task_constructor {
MOVEIT_CLASS_FORWARD(Stage) MOVEIT_CLASS_FORWARD(Stage);
MOVEIT_CLASS_FORWARD(SolutionBase) MOVEIT_CLASS_FORWARD(SolutionBase);
class TaskPrivate; class TaskPrivate;
class IntrospectionPrivate; class IntrospectionPrivate;

View File

@ -6,12 +6,12 @@
#include <functional> #include <functional>
namespace planning_scene { namespace planning_scene {
MOVEIT_CLASS_FORWARD(PlanningScene) MOVEIT_CLASS_FORWARD(PlanningScene);
} }
namespace moveit { namespace moveit {
namespace core { namespace core {
MOVEIT_CLASS_FORWARD(RobotState) MOVEIT_CLASS_FORWARD(RobotState);
MOVEIT_CLASS_FORWARD(LinkModel) MOVEIT_CLASS_FORWARD(LinkModel);
} // namespace core } // namespace core
} // namespace moveit } // namespace moveit

View File

@ -44,7 +44,7 @@ namespace moveit {
namespace task_constructor { namespace task_constructor {
namespace solvers { namespace solvers {
MOVEIT_CLASS_FORWARD(CartesianPath) MOVEIT_CLASS_FORWARD(CartesianPath);
/** Use MoveIt's computeCartesianPath() to generate a straigh-line path between to scenes */ /** Use MoveIt's computeCartesianPath() to generate a straigh-line path between to scenes */
class CartesianPath : public PlannerInterface class CartesianPath : public PlannerInterface

View File

@ -45,7 +45,7 @@ namespace moveit {
namespace task_constructor { namespace task_constructor {
namespace solvers { namespace solvers {
MOVEIT_CLASS_FORWARD(JointInterpolationPlanner) MOVEIT_CLASS_FORWARD(JointInterpolationPlanner);
/** Interpolate a trajectory between states in joint space /** Interpolate a trajectory between states in joint space
* *

View File

@ -42,14 +42,14 @@
#include <moveit/macros/class_forward.h> #include <moveit/macros/class_forward.h>
namespace planning_pipeline { namespace planning_pipeline {
MOVEIT_CLASS_FORWARD(PlanningPipeline) MOVEIT_CLASS_FORWARD(PlanningPipeline);
} }
namespace moveit { namespace moveit {
namespace task_constructor { namespace task_constructor {
namespace solvers { namespace solvers {
MOVEIT_CLASS_FORWARD(PipelinePlanner) MOVEIT_CLASS_FORWARD(PipelinePlanner);
/** Use MoveIt's PlanningPipeline to plan a trajectory between to scenes */ /** Use MoveIt's PlanningPipeline to plan a trajectory between to scenes */
class PipelinePlanner : public PlannerInterface class PipelinePlanner : public PlannerInterface

View File

@ -44,16 +44,16 @@
#include <Eigen/Geometry> #include <Eigen/Geometry>
namespace planning_scene { namespace planning_scene {
MOVEIT_CLASS_FORWARD(PlanningScene) MOVEIT_CLASS_FORWARD(PlanningScene);
} }
namespace robot_trajectory { namespace robot_trajectory {
MOVEIT_CLASS_FORWARD(RobotTrajectory) MOVEIT_CLASS_FORWARD(RobotTrajectory);
} }
namespace moveit { namespace moveit {
namespace core { namespace core {
MOVEIT_CLASS_FORWARD(LinkModel) MOVEIT_CLASS_FORWARD(LinkModel);
MOVEIT_CLASS_FORWARD(RobotModel) MOVEIT_CLASS_FORWARD(RobotModel);
MOVEIT_CLASS_FORWARD(JointModelGroup) MOVEIT_CLASS_FORWARD(JointModelGroup);
} // namespace core } // namespace core
} // namespace moveit } // namespace moveit
@ -61,7 +61,7 @@ namespace moveit {
namespace task_constructor { namespace task_constructor {
namespace solvers { namespace solvers {
MOVEIT_CLASS_FORWARD(PlannerInterface) MOVEIT_CLASS_FORWARD(PlannerInterface);
class PlannerInterface class PlannerInterface
{ {
// these properties take precedence over stage properties // these properties take precedence over stage properties

View File

@ -52,20 +52,20 @@
namespace moveit { namespace moveit {
namespace core { namespace core {
MOVEIT_CLASS_FORWARD(RobotModel) MOVEIT_CLASS_FORWARD(RobotModel);
} }
} // namespace moveit } // namespace moveit
namespace planning_scene { namespace planning_scene {
MOVEIT_CLASS_FORWARD(PlanningScene) MOVEIT_CLASS_FORWARD(PlanningScene);
} }
namespace planning_pipeline { namespace planning_pipeline {
MOVEIT_CLASS_FORWARD(PlanningPipeline) MOVEIT_CLASS_FORWARD(PlanningPipeline);
} }
namespace robot_trajectory { namespace robot_trajectory {
MOVEIT_CLASS_FORWARD(RobotTrajectory) MOVEIT_CLASS_FORWARD(RobotTrajectory);
} }
namespace moveit { namespace moveit {
@ -108,8 +108,8 @@ constexpr InterfaceFlags UNKNOWN;
constexpr InterfaceFlags START_IF_MASK({ READS_START, WRITES_PREV_END }); constexpr InterfaceFlags START_IF_MASK({ READS_START, WRITES_PREV_END });
constexpr InterfaceFlags END_IF_MASK({ READS_END, WRITES_NEXT_START }); constexpr InterfaceFlags END_IF_MASK({ READS_END, WRITES_NEXT_START });
MOVEIT_CLASS_FORWARD(Interface) MOVEIT_CLASS_FORWARD(Interface);
MOVEIT_CLASS_FORWARD(Stage) MOVEIT_CLASS_FORWARD(Stage);
class InterfaceState; class InterfaceState;
using InterfaceStatePair = std::pair<const InterfaceState&, const InterfaceState&>; using InterfaceStatePair = std::pair<const InterfaceState&, const InterfaceState&>;

View File

@ -43,8 +43,8 @@
namespace moveit { namespace moveit {
namespace core { namespace core {
MOVEIT_CLASS_FORWARD(RobotState) MOVEIT_CLASS_FORWARD(RobotState);
MOVEIT_CLASS_FORWARD(JointModelGroup) MOVEIT_CLASS_FORWARD(JointModelGroup);
} // namespace core } // namespace core
} // namespace moveit } // namespace moveit

View File

@ -45,7 +45,7 @@
namespace moveit { namespace moveit {
namespace core { namespace core {
MOVEIT_CLASS_FORWARD(RobotState) MOVEIT_CLASS_FORWARD(RobotState);
} }
} // namespace moveit } // namespace moveit

View File

@ -46,7 +46,7 @@
namespace moveit { namespace moveit {
namespace core { namespace core {
MOVEIT_CLASS_FORWARD(JointModelGroup) MOVEIT_CLASS_FORWARD(JointModelGroup);
} }
} // namespace moveit } // namespace moveit

View File

@ -44,7 +44,7 @@ namespace moveit {
namespace task_constructor { namespace task_constructor {
namespace solvers { namespace solvers {
MOVEIT_CLASS_FORWARD(CartesianPath) MOVEIT_CLASS_FORWARD(CartesianPath);
} }
namespace stages { namespace stages {

View File

@ -39,7 +39,7 @@
namespace moveit { namespace moveit {
namespace core { namespace core {
MOVEIT_CLASS_FORWARD(RobotState) MOVEIT_CLASS_FORWARD(RobotState);
} }
} // namespace moveit } // namespace moveit

View File

@ -43,7 +43,7 @@
namespace moveit { namespace moveit {
namespace core { namespace core {
MOVEIT_CLASS_FORWARD(RobotModel) MOVEIT_CLASS_FORWARD(RobotModel);
} }
} // namespace moveit } // namespace moveit
namespace moveit { namespace moveit {

View File

@ -52,21 +52,21 @@
#include <functional> #include <functional>
namespace planning_scene { namespace planning_scene {
MOVEIT_CLASS_FORWARD(PlanningScene) MOVEIT_CLASS_FORWARD(PlanningScene);
} }
namespace robot_trajectory { namespace robot_trajectory {
MOVEIT_CLASS_FORWARD(RobotTrajectory) MOVEIT_CLASS_FORWARD(RobotTrajectory);
} }
namespace moveit { namespace moveit {
namespace task_constructor { namespace task_constructor {
class SolutionBase; class SolutionBase;
MOVEIT_CLASS_FORWARD(InterfaceState) MOVEIT_CLASS_FORWARD(InterfaceState);
MOVEIT_CLASS_FORWARD(Interface) MOVEIT_CLASS_FORWARD(Interface);
MOVEIT_CLASS_FORWARD(Stage) MOVEIT_CLASS_FORWARD(Stage);
MOVEIT_CLASS_FORWARD(Introspection) MOVEIT_CLASS_FORWARD(Introspection);
/** InterfaceState describes a potential start or goal state for a planning stage. /** InterfaceState describes a potential start or goal state for a planning stage.
* *
@ -296,7 +296,7 @@ private:
const InterfaceState* start_ = nullptr; const InterfaceState* start_ = nullptr;
const InterfaceState* end_ = nullptr; const InterfaceState* end_ = nullptr;
}; };
MOVEIT_CLASS_FORWARD(SolutionBase) MOVEIT_CLASS_FORWARD(SolutionBase);
/// SubTrajectory connects interface states of ComputeStages /// SubTrajectory connects interface states of ComputeStages
class SubTrajectory : public SolutionBase class SubTrajectory : public SolutionBase
@ -318,7 +318,7 @@ private:
// actual trajectory, might be empty // actual trajectory, might be empty
robot_trajectory::RobotTrajectoryConstPtr trajectory_; robot_trajectory::RobotTrajectoryConstPtr trajectory_;
}; };
MOVEIT_CLASS_FORWARD(SubTrajectory) MOVEIT_CLASS_FORWARD(SubTrajectory);
/** Sequence of individual sub solutions /** Sequence of individual sub solutions
* *
@ -350,7 +350,7 @@ private:
/// series of sub solutions /// series of sub solutions
container_type subsolutions_; container_type subsolutions_;
}; };
MOVEIT_CLASS_FORWARD(SolutionSequence) MOVEIT_CLASS_FORWARD(SolutionSequence);
/** Wrap an existing solution /** Wrap an existing solution
* *

View File

@ -50,17 +50,17 @@
namespace moveit { namespace moveit {
namespace core { namespace core {
MOVEIT_CLASS_FORWARD(RobotModel) MOVEIT_CLASS_FORWARD(RobotModel);
MOVEIT_CLASS_FORWARD(RobotState) MOVEIT_CLASS_FORWARD(RobotState);
} // namespace core } // namespace core
} // namespace moveit } // namespace moveit
namespace moveit { namespace moveit {
namespace task_constructor { namespace task_constructor {
MOVEIT_CLASS_FORWARD(Stage) MOVEIT_CLASS_FORWARD(Stage);
MOVEIT_CLASS_FORWARD(ContainerBase) MOVEIT_CLASS_FORWARD(ContainerBase);
MOVEIT_CLASS_FORWARD(Task) MOVEIT_CLASS_FORWARD(Task);
class TaskPrivate; class TaskPrivate;
/** A Task is the root of a tree of stages. /** A Task is the root of a tree of stages.

View File

@ -42,7 +42,7 @@
#include <moveit/task_constructor/task.h> #include <moveit/task_constructor/task.h>
namespace robot_model_loader { namespace robot_model_loader {
MOVEIT_CLASS_FORWARD(RobotModelLoader) MOVEIT_CLASS_FORWARD(RobotModelLoader);
} }
namespace moveit { namespace moveit {

View File

@ -4,7 +4,7 @@
namespace moveit { namespace moveit {
namespace core { namespace core {
MOVEIT_CLASS_FORWARD(RobotModel) MOVEIT_CLASS_FORWARD(RobotModel);
} }
} // namespace moveit } // namespace moveit

View File

@ -42,9 +42,9 @@
namespace moveit_rviz_plugin { namespace moveit_rviz_plugin {
MOVEIT_CLASS_FORWARD(BaseTaskModel) MOVEIT_CLASS_FORWARD(BaseTaskModel);
MOVEIT_CLASS_FORWARD(TaskListModel) MOVEIT_CLASS_FORWARD(TaskListModel);
MOVEIT_CLASS_FORWARD(TaskDisplay) MOVEIT_CLASS_FORWARD(TaskDisplay);
/** MetaTaskListModel maintains a model of multiple registered TaskListModels, /** MetaTaskListModel maintains a model of multiple registered TaskListModels,
* which are grouped in a hierarchical fashion according to the name of the * which are grouped in a hierarchical fashion according to the name of the

View File

@ -57,16 +57,16 @@ class RosTopicProperty;
namespace moveit { namespace moveit {
namespace core { namespace core {
MOVEIT_CLASS_FORWARD(RobotModel) MOVEIT_CLASS_FORWARD(RobotModel);
} }
} // namespace moveit } // namespace moveit
namespace rdf_loader { namespace rdf_loader {
MOVEIT_CLASS_FORWARD(RDFLoader) MOVEIT_CLASS_FORWARD(RDFLoader);
} }
namespace moveit_rviz_plugin { namespace moveit_rviz_plugin {
MOVEIT_CLASS_FORWARD(DisplaySolution) MOVEIT_CLASS_FORWARD(DisplaySolution);
class TaskListModel; class TaskListModel;
class TaskDisplay : public rviz::Display class TaskDisplay : public rviz::Display

View File

@ -60,8 +60,8 @@ class DisplayContext;
namespace moveit_rviz_plugin { namespace moveit_rviz_plugin {
MOVEIT_CLASS_FORWARD(DisplaySolution) MOVEIT_CLASS_FORWARD(DisplaySolution);
MOVEIT_CLASS_FORWARD(RemoteTaskModel) MOVEIT_CLASS_FORWARD(RemoteTaskModel);
using StageFactory = PluginlibFactory<moveit::task_constructor::Stage>; using StageFactory = PluginlibFactory<moveit::task_constructor::Stage>;
using StageFactoryPtr = std::shared_ptr<StageFactory>; using StageFactoryPtr = std::shared_ptr<StageFactory>;

View File

@ -54,8 +54,8 @@ class EnumProperty;
namespace moveit_rviz_plugin { namespace moveit_rviz_plugin {
class TaskSolutionVisualization; class TaskSolutionVisualization;
MOVEIT_CLASS_FORWARD(TaskListModel) MOVEIT_CLASS_FORWARD(TaskListModel);
MOVEIT_CLASS_FORWARD(TaskPanel) MOVEIT_CLASS_FORWARD(TaskPanel);
/// Base class for all sub panels within the Task Panel /// Base class for all sub panels within the Task Panel
class SubPanel : public QWidget class SubPanel : public QWidget

View File

@ -41,14 +41,14 @@
namespace moveit { namespace moveit {
namespace core { namespace core {
MOVEIT_CLASS_FORWARD(RobotState) MOVEIT_CLASS_FORWARD(RobotState);
} }
} // namespace moveit } // namespace moveit
namespace planning_scene { namespace planning_scene {
MOVEIT_CLASS_FORWARD(PlanningScene) MOVEIT_CLASS_FORWARD(PlanningScene);
} }
namespace robot_trajectory { namespace robot_trajectory {
MOVEIT_CLASS_FORWARD(RobotTrajectory) MOVEIT_CLASS_FORWARD(RobotTrajectory);
} }
namespace Ogre { namespace Ogre {
class SceneNode; class SceneNode;
@ -59,8 +59,8 @@ class DisplayContext;
namespace moveit_rviz_plugin { namespace moveit_rviz_plugin {
MOVEIT_CLASS_FORWARD(DisplaySolution) MOVEIT_CLASS_FORWARD(DisplaySolution);
MOVEIT_CLASS_FORWARD(MarkerVisualization) MOVEIT_CLASS_FORWARD(MarkerVisualization);
/** Class representing a task solution for display */ /** Class representing a task solution for display */
class DisplaySolution class DisplaySolution

View File

@ -17,17 +17,17 @@ class MarkerBase;
} // namespace rviz } // namespace rviz
namespace planning_scene { namespace planning_scene {
MOVEIT_CLASS_FORWARD(PlanningScene) MOVEIT_CLASS_FORWARD(PlanningScene);
} }
namespace moveit { namespace moveit {
namespace core { namespace core {
MOVEIT_CLASS_FORWARD(RobotState) MOVEIT_CLASS_FORWARD(RobotState);
} }
} // namespace moveit } // namespace moveit
namespace moveit_rviz_plugin { namespace moveit_rviz_plugin {
MOVEIT_CLASS_FORWARD(MarkerVisualization) MOVEIT_CLASS_FORWARD(MarkerVisualization);
/** Container for all markers created from a vector of Marker messages /** Container for all markers created from a vector of Marker messages
* *

View File

@ -65,22 +65,22 @@ class PanelDockWidget;
namespace moveit { namespace moveit {
namespace core { namespace core {
MOVEIT_CLASS_FORWARD(RobotModel) MOVEIT_CLASS_FORWARD(RobotModel);
} }
} // namespace moveit } // namespace moveit
namespace planning_scene { namespace planning_scene {
MOVEIT_CLASS_FORWARD(PlanningScene) MOVEIT_CLASS_FORWARD(PlanningScene);
} }
namespace robot_trajectory { namespace robot_trajectory {
MOVEIT_CLASS_FORWARD(RobotTrajectory) MOVEIT_CLASS_FORWARD(RobotTrajectory);
} }
namespace moveit_rviz_plugin { namespace moveit_rviz_plugin {
MOVEIT_CLASS_FORWARD(RobotStateVisualization) MOVEIT_CLASS_FORWARD(RobotStateVisualization);
MOVEIT_CLASS_FORWARD(TaskSolutionVisualization) MOVEIT_CLASS_FORWARD(TaskSolutionVisualization);
MOVEIT_CLASS_FORWARD(PlanningSceneRender) MOVEIT_CLASS_FORWARD(PlanningSceneRender);
MOVEIT_CLASS_FORWARD(DisplaySolution) MOVEIT_CLASS_FORWARD(DisplaySolution);
class TaskSolutionPanel; class TaskSolutionPanel;
class MarkerVisualizationProperty; class MarkerVisualizationProperty;