Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008 #ifndef DESCARTES_CORE_PATH_PLANNER_BASE_H_
00009 #define DESCARTES_CORE_PATH_PLANNER_BASE_H_
00010
00011 #include <descartes_core/trajectory_pt.h>
00012 #include <descartes_core/robot_model.h>
00013 #include <vector>
00014
00015 namespace descartes_core
00016 {
00017 namespace PlannerErrors
00018 {
00019 enum PlannerError
00020 {
00021 OK = 1,
00022 IK_NOT_AVAILABLE= -1,
00023 FX_NOT_AVAILABLE = -2,
00024 SELF_COLLISION_FOUND = -3 ,
00025 ENVIRONMENT_COLLISION_FOUND = -4 ,
00026 PLANNING_TIMEOUT = -5,
00027 EMPTY_PATH = -6,
00028 SPEED_LIMIT_EXCEEDED = -7,
00029 ACCELERATION_LIMIT_EXCEEDED = -8,
00030 MAX_TRAJECTORY_SIZE_EXCEEDED = -9 ,
00031 UNINITIALIZED = -10,
00032 INVALID_ID = -11,
00033 INCOMPLETE_PATH = -12,
00034 INVALID_CONFIGURATION_PARAMETER = -13,
00035 UKNOWN = -99
00036 };
00037 }
00038 typedef PlannerErrors::PlannerError PlannerError;
00039
00040 typedef std::map<std::string,std::string> PlannerConfig;
00041
00042
00043 DESCARTES_CLASS_FORWARD(PathPlannerBase);
00044 class PathPlannerBase
00045 {
00046 public:
00047 virtual ~PathPlannerBase(){}
00048
00054 virtual bool initialize(RobotModelConstPtr model) = 0;
00055
00060 virtual bool setConfig( const PlannerConfig& config) = 0;
00061
00066 virtual void getConfig(PlannerConfig& config) const = 0;
00067
00073 virtual bool planPath(const std::vector<TrajectoryPtPtr>& traj) = 0;
00074
00079 virtual bool getPath(std::vector<TrajectoryPtPtr>& path) const = 0;
00080
00085 virtual bool addAfter(const TrajectoryPt::ID& ref_id,TrajectoryPtPtr tp) = 0;
00086
00091 virtual bool addBefore(const TrajectoryPt::ID& ref_id,TrajectoryPtPtr tp) = 0;
00092
00097 virtual bool remove(const TrajectoryPt::ID& ref_id) = 0;
00098
00103 virtual bool modify(const TrajectoryPt::ID& ref_id,TrajectoryPtPtr tp) = 0;
00104
00108 virtual int getErrorCode() const = 0;
00109
00114 virtual bool getErrorMessage(int error_code, std::string& msg) const = 0;
00115
00116 protected:
00117 PathPlannerBase(){}
00118 };
00119
00120 }
00121
00122 #endif