GraspModel.h
Go to the documentation of this file.
00001 
00014 #ifndef RAIL_PICK_AND_PLACE_GRASPDB_GRASP_MODEL_H_
00015 #define RAIL_PICK_AND_PLACE_GRASPDB_GRASP_MODEL_H_
00016 
00017 // graspdb
00018 #include "Grasp.h"
00019 
00020 // ROS
00021 #include <rail_pick_and_place_msgs/GraspModel.h>
00022 #include <sensor_msgs/PointCloud2.h>
00023 
00024 // C++ Standard Library
00025 #include <string>
00026 #include <vector>
00027 
00028 namespace rail
00029 {
00030 namespace pick_and_place
00031 {
00032 namespace graspdb
00033 {
00034 
00044 class GraspModel : public Entity
00045 {
00046 public:
00058   GraspModel(const uint32_t id = Entity::UNSET_ID, const std::string &object_name = "",
00059       const std::vector<Grasp> &grasps = std::vector<Grasp>(),
00060       const sensor_msgs::PointCloud2 &point_cloud = sensor_msgs::PointCloud2(),
00061       const time_t created = Entity::UNSET_TIME);
00062 
00073   GraspModel(const std::string &object_name, const std::vector<Grasp> &grasps,
00074       const sensor_msgs::PointCloud2 &point_cloud);
00075 
00083   GraspModel(const rail_pick_and_place_msgs::GraspModel &gm);
00084 
00092   const std::string &getObjectName() const;
00093 
00101   void setObjectName(const std::string &object_name);
00102 
00110   const std::vector<Grasp> &getGrasps() const;
00111 
00119   std::vector<Grasp> &getGrasps();
00120 
00128   size_t getNumGrasps() const;
00129 
00139   const Grasp &getGrasp(const size_t index) const;
00140 
00150   Grasp &getGrasp(const size_t index);
00151 
00159   void addGrasp(const Grasp &grasp);
00160 
00169   void removeGrasp(const size_t index);
00170 
00179   const Grasp &getBestGrasp() const;
00180 
00189   Grasp &getBestGrasp();
00190 
00199   size_t getBestGraspIndex() const;
00200 
00209   double getBestSuccessRate() const;
00210 
00219   const Grasp &getWorstGrasp() const;
00220 
00229   Grasp &getWorstGrasp();
00230 
00239   size_t getWorstGraspIndex() const;
00240 
00249   double getWorstSuccessRate() const;
00250 
00258   const sensor_msgs::PointCloud2 &getPointCloud() const;
00259 
00267   sensor_msgs::PointCloud2 &getPointCloud();
00268 
00276   void setPointCloud(const sensor_msgs::PointCloud2 &point_cloud);
00277 
00283   rail_pick_and_place_msgs::GraspModel toROSGraspModelMessage() const;
00284 
00285 private:
00287   std::string object_name_;
00289   std::vector<Grasp> grasps_;
00291   sensor_msgs::PointCloud2 point_cloud_;
00292 };
00293 
00294 }
00295 }
00296 }
00297 
00298 #endif


graspdb
Author(s): Russell Toris
autogenerated on Sun Mar 6 2016 11:38:59