Public Member Functions | Private Attributes
rail::pick_and_place::graspdb::Grasp Class Reference

A grasp database entity. More...

#include <Grasp.h>

Inheritance diagram for rail::pick_and_place::graspdb::Grasp:
Inheritance graph
[legend]

List of all members.

Public Member Functions

uint32_t getAttempts () const
 Attempts value accessor.
const std::string & getEefFrameID () const
 End effector frame ID value accessor.
uint32_t getGraspModelID () const
 Grasp model ID value accessor.
const PosegetGraspPose () const
 Grasp pose value accessor (immutable).
PosegetGraspPose ()
 Grasp pose value accessor.
uint32_t getSuccesses () const
 Successes value accessor.
double getSuccessRate () const
 Get the success rate.
 Grasp (const uint32_t id=Entity::UNSET_ID, const uint32_t grasp_model_id=Entity::UNSET_ID, const Pose &grasp_pose=Pose(), const std::string &eef_frame_id="", const uint32_t successes=0, const uint32_t attempts=0, const time_t created=Entity::UNSET_TIME)
 Create a new Grasp.
 Grasp (const Pose &grasp_pose, const uint32_t grasp_model_id, const std::string &eef_frame_id, const uint32_t successes, const uint32_t attempts)
 Create a new Grasp.
 Grasp (const rail_pick_and_place_msgs::GraspWithSuccessRate &g, const uint32_t grasp_model_id)
 Create a new Grasp.
void setAttempts (const uint32_t attempts)
 Attempts value mutator.
void setEefFrameID (const std::string &eef_frame_id)
 End effector frame ID value mutator.
void setGraspModelID (const uint32_t grasp_model_id)
 Grasp model ID value mutator.
void setGraspPose (const Pose &grasp_pose)
 Grasp pose value mutator.
void setSuccesses (const uint32_t successes)
 Successes value mutator.
rail_pick_and_place_msgs::GraspWithSuccessRate toROSGraspWithSuccessRateMessage () const

Private Attributes

uint32_t attempts_
std::string eef_frame_id_
uint32_t grasp_model_id_
Pose grasp_pose_
uint32_t successes_

Detailed Description

A grasp database entity.

A grasp contains information about a single grasp in the grasp database. This contains information about the grasp pose, end effector frame identifier, number of recorded successful grasps, number of recorded attempted grasps, and associated model ID. 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 43 of file Grasp.h.


Constructor & Destructor Documentation

rail::pick_and_place::graspdb::Grasp::Grasp ( const uint32_t  id = Entity::UNSET_ID,
const uint32_t  grasp_model_id = Entity::UNSET_ID,
const Pose grasp_pose = Pose(),
const std::string &  eef_frame_id = "",
const uint32_t  successes = 0,
const uint32_t  attempts = 0,
const time_t  created = Entity::UNSET_TIME 
)

Create a new Grasp.

Creates a new Grasp with the given values. This constructor assumes a valid ID and timestamp are known.

Parameters:
idThe unique ID of the database entry (defaults to 0).
grasp_model_idThe ID of the associated grasp model entry (defaults to 0).
grasp_poseThe pose of the grasp (defaults to an empty Pose).
eef_frame_idThe frame identifier for the end effector (defaults to the empty string).
successesThe number of recorded successful grasps (defaults to 0).
attemptsThe number of recorded attempted grasps (defaults to 0).
createdThe created timestamp (defaults to 0).
rail::pick_and_place::graspdb::Grasp::Grasp ( const Pose grasp_pose,
const uint32_t  grasp_model_id,
const std::string &  eef_frame_id,
const uint32_t  successes,
const uint32_t  attempts 
)

Create a new Grasp.

Creates a new Grasp with the given values. This constructor assumes no valid ID and timestamp are known (e.g., for use when inserting into the database).

Parameters:
grasp_poseThe pose of the grasp.
grasp_model_idThe valid ID of the associated grasp model entry.
successesThe number of recorded successful grasps.
attemptsThe number of recorded attempted grasps.
eef_frame_idThe frame identifier for the end effector used (defaults to the empty string).
Grasp::Grasp ( const rail_pick_and_place_msgs::GraspWithSuccessRate &  g,
const uint32_t  grasp_model_id 
)

Create a new Grasp.

Creates a new Grasp with the given values the ROS message. This constructor assumes no valid ID and timestamp are known.

Parameters:
gdThe ROS grasp message to extract values from.
grasp_model_idThe valid ID of the associated grasp model entry.

Definition at line 39 of file Grasp.cpp.


Member Function Documentation

uint32_t Grasp::getAttempts ( ) const

Attempts value accessor.

Get the attempts value of this Grasp.

Returns:
The attempts value.

Definition at line 93 of file Grasp.cpp.

const string & Grasp::getEefFrameID ( ) const

End effector frame ID value accessor.

Get the end effector frame ID value of this Grasp.

Returns:
The end effector frame ID value.

Definition at line 73 of file Grasp.cpp.

uint32_t Grasp::getGraspModelID ( ) const

Grasp model ID value accessor.

Get the grasp model ID value of this Grasp.

Returns:
The grasp model ID value.

Definition at line 48 of file Grasp.cpp.

const Pose & Grasp::getGraspPose ( ) const

Grasp pose value accessor (immutable).

Get the grasp pose value of this Grasp.

Returns:
The grasp pose value.

Definition at line 58 of file Grasp.cpp.

Grasp pose value accessor.

Get the grasp pose value of this Grasp.

Returns:
The grasp pose value.

Definition at line 63 of file Grasp.cpp.

uint32_t Grasp::getSuccesses ( ) const

Successes value accessor.

Get the successes value of this Grasp.

Returns:
The successes value.

Definition at line 83 of file Grasp.cpp.

double Grasp::getSuccessRate ( ) const

Get the success rate.

Set the success rate of this Grasp. A grasp that has no attempts will return 0.

Parameters:
attemptsThe success rate of this Grasp.

Definition at line 103 of file Grasp.cpp.

void Grasp::setAttempts ( const uint32_t  attempts)

Attempts value mutator.

Set the attempts value of this Grasp.

Parameters:
attemptsThe new attempts value.

Definition at line 98 of file Grasp.cpp.

void Grasp::setEefFrameID ( const std::string &  eef_frame_id)

End effector frame ID value mutator.

Set the end effector frame ID value of this Grasp.

Parameters:
eef_frame_idThe new object name value.

Definition at line 78 of file Grasp.cpp.

void Grasp::setGraspModelID ( const uint32_t  grasp_model_id)

Grasp model ID value mutator.

Set the grasp model ID value of this Grasp.

Parameters:
grasp_model_idThe new grasp model ID value.

Definition at line 53 of file Grasp.cpp.

void Grasp::setGraspPose ( const Pose grasp_pose)

Grasp pose value mutator.

Set the grasp pose value of this Grasp.

Parameters:
grasp_poseThe new grasp pose value.

Definition at line 68 of file Grasp.cpp.

void Grasp::setSuccesses ( const uint32_t  successes)

Successes value mutator.

Set the successes value of this Grasp.

Parameters:
successesThe new successes value.

Definition at line 88 of file Grasp.cpp.

rail_pick_and_place_msgs::GraspWithSuccessRate Grasp::toROSGraspWithSuccessRateMessage ( ) const

Converts this Grasp object into a ROS GraspWithSuccessRate message.

Returns:
The ROS GraspWithSuccessRate message with this grasp data.

Definition at line 110 of file Grasp.cpp.


Member Data Documentation

Definition at line 212 of file Grasp.h.

The name of the object and end effector frame identifier for this demonstration entry.

Definition at line 208 of file Grasp.h.

The ID of the associated grasp model.

Definition at line 206 of file Grasp.h.

The grasp pose data.

Definition at line 210 of file Grasp.h.

The success rate information.

Definition at line 212 of file Grasp.h.


The documentation for this class was generated from the following files:


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