GraspDemonstration.cpp
Go to the documentation of this file.
00001 
00014 // graspdb
00015 #include "graspdb/GraspDemonstration.h"
00016 
00017 using namespace std;
00018 using namespace rail::pick_and_place::graspdb;
00019 
00020 GraspDemonstration::GraspDemonstration(const uint32_t id, const string &object_name, const Pose &grasp_pose,
00021                                        const string &eef_frame_id, const sensor_msgs::PointCloud2 &point_cloud,
00022                                        const sensor_msgs::Image &image, const time_t created)
00023     : Entity(id, created),
00024       object_name_(object_name), grasp_pose_(grasp_pose), eef_frame_id_(eef_frame_id), point_cloud_(point_cloud),
00025       image_(image)
00026 {
00027 }
00028 
00029 GraspDemonstration::GraspDemonstration(const string &object_name, const Pose &grasp_pose, const string &eef_frame_id,
00030                                        const sensor_msgs::PointCloud2 &point_cloud, const sensor_msgs::Image &image)
00031     : object_name_(object_name), grasp_pose_(grasp_pose), eef_frame_id_(eef_frame_id), point_cloud_(point_cloud),
00032       image_(image)
00033 {
00034 }
00035 
00036 GraspDemonstration::GraspDemonstration(const rail_pick_and_place_msgs::GraspDemonstration &gd)
00037     : Entity(gd.id, gd.created.sec),
00038       object_name_(gd.object_name), grasp_pose_(gd.grasp_pose), eef_frame_id_(gd.eef_frame_id),
00039       point_cloud_(gd.point_cloud), image_(gd.image)
00040 {
00041 }
00042 
00043 const string &GraspDemonstration::getObjectName() const
00044 {
00045   return object_name_;
00046 }
00047 
00048 void GraspDemonstration::setObjectName(const string &object_name)
00049 {
00050   object_name_ = object_name;
00051 }
00052 
00053 const Pose &GraspDemonstration::getGraspPose() const
00054 {
00055   return grasp_pose_;
00056 }
00057 
00058 Pose &GraspDemonstration::getGraspPose()
00059 {
00060   return grasp_pose_;
00061 }
00062 
00063 void GraspDemonstration::setGraspPose(const Pose &grasp_pose)
00064 {
00065   grasp_pose_ = grasp_pose;
00066 }
00067 
00068 const string &GraspDemonstration::getEefFrameID() const
00069 {
00070   return eef_frame_id_;
00071 }
00072 
00073 void GraspDemonstration::setEefFrameID(const string &eef_frame_id)
00074 {
00075   eef_frame_id_ = eef_frame_id;
00076 }
00077 
00078 const sensor_msgs::PointCloud2 &GraspDemonstration::getPointCloud() const
00079 {
00080   return point_cloud_;
00081 }
00082 
00083 sensor_msgs::PointCloud2 &GraspDemonstration::getPointCloud()
00084 {
00085   return point_cloud_;
00086 }
00087 
00088 void GraspDemonstration::setPointCloud(const sensor_msgs::PointCloud2 &point_cloud)
00089 {
00090   point_cloud_ = point_cloud;
00091 }
00092 
00093 const sensor_msgs::Image &GraspDemonstration::getImage() const
00094 {
00095   return image_;
00096 }
00097 
00098 sensor_msgs::Image &GraspDemonstration::getImage()
00099 {
00100   return image_;
00101 }
00102 
00103 void GraspDemonstration::setImage(const sensor_msgs::Image &image)
00104 {
00105   image_ = image;
00106 }
00107 
00108 rail_pick_and_place_msgs::GraspDemonstration GraspDemonstration::toROSGraspDemonstrationMessage() const
00109 {
00110   rail_pick_and_place_msgs::GraspDemonstration gd;
00111   gd.id = this->getID();
00112   gd.object_name = object_name_;
00113   gd.grasp_pose = grasp_pose_.toROSPoseStampedMessage();
00114   gd.eef_frame_id = eef_frame_id_;
00115   gd.point_cloud = point_cloud_;
00116   gd.image = image_;
00117   gd.created.nsec = 0;
00118   gd.created.sec = this->getCreated();
00119   return gd;
00120 }


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