Trained grasp model information. More...
#include <GraspModel.h>

Public Member Functions | |
| void | addGrasp (const Grasp &grasp) |
| Grasp adder. | |
| const Grasp & | getBestGrasp () const |
| Get the best grasp. | |
| Grasp & | getBestGrasp () |
| Get the best grasp (immutable). | |
| size_t | getBestGraspIndex () const |
| Get the best grasp index. | |
| double | getBestSuccessRate () const |
| Get the highest success rate. | |
| const Grasp & | getGrasp (const size_t index) const |
| Grasp pose value accessor (immutable). | |
| Grasp & | getGrasp (const size_t index) |
| Grasp pose value accessor. | |
| const std::vector< Grasp > & | getGrasps () const |
| Grasps value accessor (immutable). | |
| std::vector< Grasp > & | getGrasps () |
| Grasps value accessor. | |
| size_t | getNumGrasps () const |
| Grasps size 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. | |
| const Grasp & | getWorstGrasp () const |
| Get the worst grasp (immutable). | |
| Grasp & | getWorstGrasp () |
| Get the worst grasp. | |
| size_t | getWorstGraspIndex () const |
| Get the worst grasp index. | |
| double | getWorstSuccessRate () const |
| Get the lowest success rate. | |
| GraspModel (const uint32_t id=Entity::UNSET_ID, const std::string &object_name="", const std::vector< Grasp > &grasps=std::vector< Grasp >(), const sensor_msgs::PointCloud2 &point_cloud=sensor_msgs::PointCloud2(), const time_t created=Entity::UNSET_TIME) | |
| Create a new GraspModel. | |
| GraspModel (const std::string &object_name, const std::vector< Grasp > &grasps, const sensor_msgs::PointCloud2 &point_cloud) | |
| Create a new GraspModel. | |
| GraspModel (const rail_pick_and_place_msgs::GraspModel &gm) | |
| Create a new GraspModel. | |
| void | removeGrasp (const size_t index) |
| Grasp remover. | |
| 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::GraspModel | toROSGraspModelMessage () const |
Private Attributes | |
| std::vector< Grasp > | grasps_ |
| std::string | object_name_ |
| sensor_msgs::PointCloud2 | point_cloud_ |
Trained grasp model information.
A grasp model contains a 3D point cloud model made up of several segmented point cloud segments from various grasp demonstrations, an object name (may be non-unique), an array of grasps for the model, and a unique identifier. This class is useful for internal data management within the graspdb library. Convenience functions are added for use with ROS messages.
Definition at line 44 of file GraspModel.h.
| rail::pick_and_place::graspdb::GraspModel::GraspModel | ( | const uint32_t | id = Entity::UNSET_ID, |
| const std::string & | object_name = "", |
||
| const std::vector< Grasp > & | grasps = std::vector< Grasp >(), |
||
| const sensor_msgs::PointCloud2 & | point_cloud = sensor_msgs::PointCloud2(), |
||
| const time_t | created = Entity::UNSET_TIME |
||
| ) |
Create a new GraspModel.
Creates a new GraspModel 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). |
| grasps | The pose of the grasp (defaults to an empty vector). |
| point_cloud | The ROS sensor_msgs/PointCloud2 message of the segmented object (defaults to empty values). |
| created | The created timestamp (defaults to 0). |
| rail::pick_and_place::graspdb::GraspModel::GraspModel | ( | const std::string & | object_name, |
| const std::vector< Grasp > & | grasps, | ||
| const sensor_msgs::PointCloud2 & | point_cloud | ||
| ) |
Create a new GraspModel.
Creates a new GraspModel 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. |
| grasps | The pose of the grasp. |
| point_cloud | The ROS sensor_msgs/PointCloud2 message of the segmented object. |
| GraspModel::GraspModel | ( | const rail_pick_and_place_msgs::GraspModel & | gm | ) |
Create a new GraspModel.
Creates a new GraspModel with the given values the ROS message.
| m | The ROS GraspModel message to extract values from. |
Definition at line 36 of file GraspModel.cpp.
| void GraspModel::addGrasp | ( | const Grasp & | grasp | ) |
Grasp adder.
Add the grasp to this GraspModel. If the grasp_model_id of the grasp does not match, it will not be added.
| grasp | The new grasp to add. |
Definition at line 97 of file GraspModel.cpp.
| const Grasp & GraspModel::getBestGrasp | ( | ) | const |
Get the best grasp.
Get the best grasp based on the highest success rate. A tie results in the smaller index.
| std::out_of_range | Thrown if there are no grasps in this grasp model. |
Definition at line 121 of file GraspModel.cpp.
Get the best grasp (immutable).
Get the best grasp based on the highest success rate. A tie results in the smaller index.
| std::out_of_range | Thrown if there are no grasps in this grasp model. |
Definition at line 133 of file GraspModel.cpp.
| size_t GraspModel::getBestGraspIndex | ( | ) | const |
Get the best grasp index.
Get the index of the best grasp based on the highest success rate. A tie results in the smaller index.
| std::out_of_range | Thrown if there are no grasps in this grasp model. |
Definition at line 145 of file GraspModel.cpp.
| double GraspModel::getBestSuccessRate | ( | ) | const |
Get the highest success rate.
Get the highest grasp success rate of this model.
| std::out_of_range | Thrown if there are no grasps in this grasp model. |
Definition at line 171 of file GraspModel.cpp.
| const Grasp & GraspModel::getGrasp | ( | const size_t | index | ) | const |
Grasp pose value accessor (immutable).
Get the grasp of this GraspModel at the given index.
| i | The index of the Pose to get. |
| std::out_of_range | Thrown if the grasp at the given index does not exist. |
Definition at line 73 of file GraspModel.cpp.
| Grasp & GraspModel::getGrasp | ( | const size_t | index | ) |
Grasp pose value accessor.
Get the grasp of this GraspModel at the given index.
| i | The index of the Pose to get. |
| std::out_of_range | Thrown if the grasp at the given index does not exist. |
Definition at line 85 of file GraspModel.cpp.
| const vector< Grasp > & GraspModel::getGrasps | ( | ) | const |
Grasps value accessor (immutable).
Get the grasps of this GraspModel.
Definition at line 58 of file GraspModel.cpp.
| vector< Grasp > & GraspModel::getGrasps | ( | ) |
Grasps value accessor.
Get the grasps of this GraspModel.
Definition at line 63 of file GraspModel.cpp.
| size_t GraspModel::getNumGrasps | ( | ) | const |
Grasps size accessor.
Get the number of grasps of this GraspModel.
Definition at line 68 of file GraspModel.cpp.
| const string & GraspModel::getObjectName | ( | ) | const |
Object name value accessor.
Get the object name value of this GraspModel.
Definition at line 48 of file GraspModel.cpp.
| const sensor_msgs::PointCloud2 & GraspModel::getPointCloud | ( | ) | const |
Point cloud accessor (immutable).
Get the point cloud message.
Definition at line 265 of file GraspModel.cpp.
| sensor_msgs::PointCloud2 & GraspModel::getPointCloud | ( | ) |
Point cloud accessor.
Get the point cloud message.
Definition at line 270 of file GraspModel.cpp.
| const Grasp & GraspModel::getWorstGrasp | ( | ) | const |
Get the worst grasp (immutable).
Get the worst grasp based on the lowest success rate. A tie results in the smaller index.
| std::out_of_range | Thrown if there are no grasps in this grasp model. |
Definition at line 193 of file GraspModel.cpp.
Get the worst grasp.
Get the worst grasp based on the lowest success rate. A tie results in the smaller index.
| std::out_of_range | Thrown if there are no grasps in this grasp model. |
Definition at line 205 of file GraspModel.cpp.
| size_t GraspModel::getWorstGraspIndex | ( | ) | const |
Get the worst grasp index.
Get the index of the worst grasp based on the lowest success rate. A tie results in the smaller index.
| std::out_of_range | Thrown if there are no grasps in this grasp model. |
Definition at line 217 of file GraspModel.cpp.
| double GraspModel::getWorstSuccessRate | ( | ) | const |
Get the lowest success rate.
Get the lowest grasp success rate of this model.
| std::out_of_range | Thrown if there are no grasps in this grasp model. |
Definition at line 243 of file GraspModel.cpp.
| void GraspModel::removeGrasp | ( | const size_t | index | ) |
Grasp remover.
Remove the grasp at the given index. An invalid index results in no effect.
| i | The index of the grasp pose to remove. |
| std::out_of_range | Thrown if the grasp at the given index does not exist. |
Definition at line 109 of file GraspModel.cpp.
| void GraspModel::setObjectName | ( | const std::string & | object_name | ) |
Object name value mutator.
Set the object name value of this GraspModel.
| object_name | The new object name value. |
Definition at line 53 of file GraspModel.cpp.
| void GraspModel::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 275 of file GraspModel.cpp.
| rail_pick_and_place_msgs::GraspModel GraspModel::toROSGraspModelMessage | ( | ) | const |
Converts this GraspModel object into a ROS GraspModel message.
Definition at line 280 of file GraspModel.cpp.
std::vector<Grasp> rail::pick_and_place::graspdb::GraspModel::grasps_ [private] |
The grasps for this model.
Definition at line 289 of file GraspModel.h.
std::string rail::pick_and_place::graspdb::GraspModel::object_name_ [private] |
The name of the object for this model.
Definition at line 287 of file GraspModel.h.
sensor_msgs::PointCloud2 rail::pick_and_place::graspdb::GraspModel::point_cloud_ [private] |
The point cloud data.
Definition at line 291 of file GraspModel.h.