Go to the documentation of this file.00001
00014 #ifndef RAIL_PICK_AND_PLACE_GRASPDB_GRASP_H_
00015 #define RAIL_PICK_AND_PLACE_GRASPDB_GRASP_H_
00016
00017
00018 #include "Entity.h"
00019 #include "Pose.h"
00020
00021
00022 #include <rail_pick_and_place_msgs/GraspWithSuccessRate.h>
00023
00024
00025 #include <string>
00026
00027 namespace rail
00028 {
00029 namespace pick_and_place
00030 {
00031 namespace graspdb
00032 {
00033
00043 class Grasp : public Entity
00044 {
00045 public:
00059 Grasp(const uint32_t id = Entity::UNSET_ID, const uint32_t grasp_model_id = Entity::UNSET_ID,
00060 const Pose &grasp_pose = Pose(), const std::string &eef_frame_id = "", const uint32_t successes = 0,
00061 const uint32_t attempts = 0, const time_t created = Entity::UNSET_TIME);
00062
00075 Grasp(const Pose &grasp_pose, const uint32_t grasp_model_id, const std::string &eef_frame_id,
00076 const uint32_t successes, const uint32_t attempts);
00077
00087 Grasp(const rail_pick_and_place_msgs::GraspWithSuccessRate &g, const uint32_t grasp_model_id);
00088
00096 uint32_t getGraspModelID() const;
00097
00105 void setGraspModelID(const uint32_t grasp_model_id);
00106
00114 const Pose &getGraspPose() const;
00115
00123 Pose &getGraspPose();
00124
00132 void setGraspPose(const Pose &grasp_pose);
00133
00141 const std::string &getEefFrameID() const;
00142
00150 void setEefFrameID(const std::string &eef_frame_id);
00151
00159 uint32_t getSuccesses() const;
00160
00168 void setSuccesses(const uint32_t successes);
00169
00177 uint32_t getAttempts() const;
00178
00186 void setAttempts(const uint32_t attempts);
00187
00195 double getSuccessRate() const;
00196
00202 rail_pick_and_place_msgs::GraspWithSuccessRate toROSGraspWithSuccessRateMessage() const;
00203
00204 private:
00206 uint32_t grasp_model_id_;
00208 std::string eef_frame_id_;
00210 Pose grasp_pose_;
00212 uint32_t successes_, attempts_;
00213 };
00214
00215 }
00216 }
00217 }
00218
00219 #endif