A grasp demonstration database entry. More...
#include <GraspDemonstration.h>
Public Member Functions | |
const std::string & | getEefFrameID () const |
End effector frame ID value accessor. | |
const Pose & | getGraspPose () const |
Grasp pose value accessor (immutable). | |
Pose & | getGraspPose () |
Grasp pose value accessor. | |
const sensor_msgs::Image & | getImage () const |
Image accessor (immutable). | |
sensor_msgs::Image & | getImage () |
Image accessor. | |
const std::string & | getObjectName () const |
Object name value accessor. | |
const sensor_msgs::PointCloud2 & | getPointCloud () const |
Point cloud accessor (immutable). | |
sensor_msgs::PointCloud2 & | getPointCloud () |
Point cloud accessor. | |
GraspDemonstration (const uint32_t id=Entity::UNSET_ID, const std::string &object_name="", const Pose &grasp_pose=Pose(), const std::string &eef_frame_id="", const sensor_msgs::PointCloud2 &point_cloud=sensor_msgs::PointCloud2(), const sensor_msgs::Image &image=sensor_msgs::Image(), const time_t created=Entity::UNSET_TIME) | |
Create a new GraspDemonstration. | |
GraspDemonstration (const std::string &object_name, const Pose &grasp_pose, const std::string &eef_frame_id, const sensor_msgs::PointCloud2 &point_cloud, const sensor_msgs::Image &image) | |
Create a new GraspDemonstration. | |
GraspDemonstration (const rail_pick_and_place_msgs::GraspDemonstration &gd) | |
Create a new GraspDemonstration. | |
void | setEefFrameID (const std::string &eef_frame_id) |
End effector frame ID value mutator. | |
void | setGraspPose (const Pose &grasp_pose) |
Grasp pose value mutator. | |
void | setImage (const sensor_msgs::Image &image) |
Image mutator. | |
void | setObjectName (const std::string &object_name) |
Object name value mutator. | |
void | setPointCloud (const sensor_msgs::PointCloud2 &point_cloud) |
Point cloud mutator. | |
rail_pick_and_place_msgs::GraspDemonstration | toROSGraspDemonstrationMessage () const |
Private Attributes | |
std::string | eef_frame_id_ |
Pose | grasp_pose_ |
sensor_msgs::Image | image_ |
std::string | object_name_ |
sensor_msgs::PointCloud2 | point_cloud_ |
A grasp demonstration database entry.
A grasp demonstration contains information about a single grasp demonstration in the grasp database. This contains information about the grasp pose, end effector frame identifier, object name, and serialized segmented point cloud. A valid database entity has an ID and created timestamp. This class is useful for internal data management within the graspdb library. Convenience functions are added for use with ROS messages.
Definition at line 45 of file GraspDemonstration.h.
rail::pick_and_place::graspdb::GraspDemonstration::GraspDemonstration | ( | const uint32_t | id = Entity::UNSET_ID , |
const std::string & | object_name = "" , |
||
const Pose & | grasp_pose = Pose() , |
||
const std::string & | eef_frame_id = "" , |
||
const sensor_msgs::PointCloud2 & | point_cloud = sensor_msgs::PointCloud2() , |
||
const sensor_msgs::Image & | image = sensor_msgs::Image() , |
||
const time_t | created = Entity::UNSET_TIME |
||
) |
Create a new GraspDemonstration.
Creates a new GraspDemonstration with the given values. This constructor assumes a valid ID and timestamp are known.
id | The unique ID of the database entry (defaults to 0). |
object_name | The name of the object grasped (defaults to the empty string). |
grasp_pose | The pose of the grasp (defaults to an empty Pose). |
eef_frame_id | The frame identifier for the end effector used (defaults to the empty string). |
point_cloud | The ROS sensor_msgs/PointCloud2 message of the segmented object (defaults to empty values). |
image | The ROS sensor_msgs/Image message of the segmented object (defaults to empty values). |
created | The created timestamp (defaults to 0). |
rail::pick_and_place::graspdb::GraspDemonstration::GraspDemonstration | ( | const std::string & | object_name, |
const Pose & | grasp_pose, | ||
const std::string & | eef_frame_id, | ||
const sensor_msgs::PointCloud2 & | point_cloud, | ||
const sensor_msgs::Image & | image | ||
) |
Create a new GraspDemonstration.
Creates a new GraspDemonstration with the given values. This constructor assumes no valid ID and timestamp are known (e.g., for use when inserting into the database).
object_name | The name of the object grasped. |
grasp_pose | The pose of the grasp. |
eef_frame_id | The frame identifier for the end effector used. |
point_cloud | The ROS sensor_msgs/PointCloud2 message of the segmented object. |
image | The ROS sensor_msgs/Image message of the segmented object. |
GraspDemonstration::GraspDemonstration | ( | const rail_pick_and_place_msgs::GraspDemonstration & | gd | ) |
Create a new GraspDemonstration.
Creates a new GraspDemonstration with the given values the ROS message.
gd | The ROS grasp demonstration message to extract values from. |
Definition at line 36 of file GraspDemonstration.cpp.
const string & GraspDemonstration::getEefFrameID | ( | ) | const |
End effector frame ID value accessor.
Get the end effector frame ID value of this GraspDemonstration.
Definition at line 68 of file GraspDemonstration.cpp.
const Pose & GraspDemonstration::getGraspPose | ( | ) | const |
Grasp pose value accessor (immutable).
Get the grasp pose value of this GraspDemonstration.
Definition at line 53 of file GraspDemonstration.cpp.
Grasp pose value accessor.
Get the grasp pose value of this GraspDemonstration.
Definition at line 58 of file GraspDemonstration.cpp.
const sensor_msgs::Image & GraspDemonstration::getImage | ( | ) | const |
Image accessor (immutable).
Get the image message.
Definition at line 93 of file GraspDemonstration.cpp.
sensor_msgs::Image & GraspDemonstration::getImage | ( | ) |
Image accessor.
Get the image message.
Definition at line 98 of file GraspDemonstration.cpp.
const string & GraspDemonstration::getObjectName | ( | ) | const |
Object name value accessor.
Get the object name value of this GraspDemonstration.
Definition at line 43 of file GraspDemonstration.cpp.
const sensor_msgs::PointCloud2 & GraspDemonstration::getPointCloud | ( | ) | const |
Point cloud accessor (immutable).
Get the point cloud message.
Definition at line 78 of file GraspDemonstration.cpp.
sensor_msgs::PointCloud2 & GraspDemonstration::getPointCloud | ( | ) |
Point cloud accessor.
Get the point cloud message.
Definition at line 83 of file GraspDemonstration.cpp.
void GraspDemonstration::setEefFrameID | ( | const std::string & | eef_frame_id | ) |
End effector frame ID value mutator.
Set the end effector frame ID value of this GraspDemonstration.
eef_frame_id | The new object name value. |
Definition at line 73 of file GraspDemonstration.cpp.
void GraspDemonstration::setGraspPose | ( | const Pose & | grasp_pose | ) |
Grasp pose value mutator.
Set the grasp pose value of this GraspDemonstration.
grasp_pose | The new grasp pose value. |
Definition at line 63 of file GraspDemonstration.cpp.
void GraspDemonstration::setImage | ( | const sensor_msgs::Image & | image | ) |
Image mutator.
Set the image message to the given values based on the ROS message.
image | The ROS Image message to store. |
Definition at line 103 of file GraspDemonstration.cpp.
void GraspDemonstration::setObjectName | ( | const std::string & | object_name | ) |
Object name value mutator.
Set the object name value of this GraspDemonstration.
object_name | The new object name value. |
Definition at line 48 of file GraspDemonstration.cpp.
void GraspDemonstration::setPointCloud | ( | const sensor_msgs::PointCloud2 & | point_cloud | ) |
Point cloud mutator.
Set the point cloud message to the given values based on the ROS message.
point_cloud | The ROS PointCloud2 message to store. |
Definition at line 88 of file GraspDemonstration.cpp.
rail_pick_and_place_msgs::GraspDemonstration GraspDemonstration::toROSGraspDemonstrationMessage | ( | ) | const |
Converts this GraspDemonstration object into a ROS GraspDemonstration message.
Definition at line 108 of file GraspDemonstration.cpp.
std::string rail::pick_and_place::graspdb::GraspDemonstration::eef_frame_id_ [private] |
Definition at line 217 of file GraspDemonstration.h.
The grasp pose data.
Definition at line 219 of file GraspDemonstration.h.
sensor_msgs::Image rail::pick_and_place::graspdb::GraspDemonstration::image_ [private] |
The RGB image data.
Definition at line 223 of file GraspDemonstration.h.
std::string rail::pick_and_place::graspdb::GraspDemonstration::object_name_ [private] |
The name of the object and end effector frame identifier for this demonstration entry.
Definition at line 217 of file GraspDemonstration.h.
sensor_msgs::PointCloud2 rail::pick_and_place::graspdb::GraspDemonstration::point_cloud_ [private] |
The point cloud data.
Definition at line 221 of file GraspDemonstration.h.