Go to the documentation of this file.00001
00014 #ifndef RAIL_PICK_AND_PLACE_GRASPDB_GRASP_DEMONSTRATION_H_
00015 #define RAIL_PICK_AND_PLACE_GRASPDB_GRASP_DEMONSTRATION_H_
00016
00017
00018 #include "Entity.h"
00019 #include "Pose.h"
00020
00021
00022 #include <rail_pick_and_place_msgs/GraspDemonstration.h>
00023 #include <sensor_msgs/Image.h>
00024 #include <sensor_msgs/PointCloud2.h>
00025
00026
00027 #include <string>
00028
00029 namespace rail
00030 {
00031 namespace pick_and_place
00032 {
00033 namespace graspdb
00034 {
00035
00045 class GraspDemonstration : public Entity
00046 {
00047 public:
00062 GraspDemonstration(const uint32_t id = Entity::UNSET_ID, const std::string &object_name = "",
00063 const Pose &grasp_pose = Pose(), const std::string &eef_frame_id = "",
00064 const sensor_msgs::PointCloud2 &point_cloud = sensor_msgs::PointCloud2(),
00065 const sensor_msgs::Image &image = sensor_msgs::Image(), const time_t created = Entity::UNSET_TIME);
00066
00079 GraspDemonstration(const std::string &object_name, const Pose &grasp_pose, const std::string &eef_frame_id,
00080 const sensor_msgs::PointCloud2 &point_cloud, const sensor_msgs::Image &image);
00081
00089 GraspDemonstration(const rail_pick_and_place_msgs::GraspDemonstration &gd);
00090
00098 const std::string &getObjectName() const;
00099
00107 void setObjectName(const std::string &object_name);
00108
00116 const Pose &getGraspPose() const;
00117
00125 Pose &getGraspPose();
00126
00134 void setGraspPose(const Pose &grasp_pose);
00135
00143 const std::string &getEefFrameID() const;
00144
00152 void setEefFrameID(const std::string &eef_frame_id);
00153
00161 const sensor_msgs::PointCloud2 &getPointCloud() const;
00162
00170 sensor_msgs::PointCloud2 &getPointCloud();
00171
00179 void setPointCloud(const sensor_msgs::PointCloud2 &point_cloud);
00180
00188 const sensor_msgs::Image &getImage() const;
00189
00197 sensor_msgs::Image &getImage();
00198
00206 void setImage(const sensor_msgs::Image &image);
00207
00213 rail_pick_and_place_msgs::GraspDemonstration toROSGraspDemonstrationMessage() const;
00214
00215 private:
00217 std::string object_name_, eef_frame_id_;
00219 Pose grasp_pose_;
00221 sensor_msgs::PointCloud2 point_cloud_;
00223 sensor_msgs::Image image_;
00224 };
00225
00226 }
00227 }
00228 }
00229
00230 #endif