SolverInterface.h
Go to the documentation of this file.
00001 
00003 #ifndef SOLVERINTERFACE_H_
00004 #define SOLVERINTERFACE_H_
00005 #include<surfacelet/SurfacePatch.h>
00006 #include<coverage_3d_arm_navigation/TrajectoryPlanner.h>
00007 #include<tf/tf.h>
00008 
00009 class SolverInterface {
00010 public:
00011 
00012     SolverInterface();
00013     SolverInterface(double max_adjacency);
00014 
00015     virtual void getSolution(std::vector<std::vector<double> >& joint_path, std::vector<tf::Pose>& pose_path,
00016         std::vector<unsigned int>& action, std::vector<unsigned int>& res_traj)= 0;
00017     virtual void getActions(const std::vector<unsigned int>& traj, std::vector<unsigned int>& actions)= 0;
00018 
00019     void setGraph(const std::vector<SurfacePatch>& patches, const std::vector<pcl::PointXYZ>&surface_points,
00020         const Eigen::MatrixXi& adjacency, const std::vector<std::vector<tf::Pose> >&coll_free_poses, const std::vector<
00021             std::vector<std::vector<std::vector<double> > > >& coll_free_ik);
00022     void setStartPose(std::vector<double> joint_pose, tf::Pose pose);
00023     void setDistMeasure(std::string measure);
00024     void setMaxAdjacency(double adjacency);
00025     double getMaxAdjacency() const;
00026 
00027 protected:
00028 
00029     std::string dist_measure_;
00030     double max_adjacency_;
00031 
00032     std::vector<double> start_joint_;
00033     tf::Pose start_pose_;
00034     std::vector<SurfacePatch> patches_;
00035     std::vector<pcl::PointXYZ> surface_points_;
00036     Eigen::MatrixXi adjacency_;
00037     std::vector<std::vector<tf::Pose> > coll_free_poses_;
00038     std::vector<std::vector<std::vector<std::vector<double> > > > coll_free_ik_;
00039     TrajectoryPlanner traj_planner_;
00040 };
00041 #endif /* SOLVERINTERFACE_H_ */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


coverage_3d_planning
Author(s): Juergen Hess
autogenerated on Wed Dec 26 2012 15:26:11