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

The main grasp database client. More...

#include <Client.h>

List of all members.

Public Member Functions

bool addGrasp (Grasp &graps) const
 Add a grasp to the database.
bool addGraspDemonstration (GraspDemonstration &gd) const
 Add a grasp demonstration to the database.
bool addGraspModel (GraspModel &gm) const
 Add a grasp model and its associated grasps to the database.
 Client (const Client &c)
 Create a new Client.
 Client (const std::string &host, const uint16_t port, const std::string &user, const std::string &password, const std::string &db)
 Create a new Client.
bool connect ()
 Create a connection to the database.
bool connected () const
 Check if there is a connection to the database.
void deleteGrasp (uint32_t id) const
 Delete a grasp from the database.
void deleteGraspDemonstration (uint32_t id) const
 Delete a grasp demonstration from the database.
void deleteGraspModel (uint32_t id) const
 Delete a grasp model from the database.
void disconnect ()
 Closes a connection to the database.
const std::string & getDatabase () const
 Database value accessor.
const std::string & getHost () const
 Host value accessor.
const std::string & getPassword () const
 Password value accessor.
uint16_t getPort () const
 Port value accessor.
bool getUniqueGraspDemonstrationObjectNames (std::vector< std::string > &names) const
 Load the unique demonstration object names from the database.
bool getUniqueGraspModelObjectNames (std::vector< std::string > &names) const
 Load the unique grasp model object names from the database.
const std::string & getUser () const
 User value accessor.
bool loadGrasp (uint32_t id, Grasp &grasp) const
 Load a grasp from the database.
bool loadGraspByGraspModelID (const uint32_t grasp_model_id, std::vector< Grasp > &grasps) const
 Load grasps from the database from an associated model ID.
bool loadGraspDemonstration (uint32_t id, GraspDemonstration &gd) const
 Load a grasp demonstration from the database.
bool loadGraspDemonstrations (std::vector< GraspDemonstration > &gds) const
 Load all grasp demonstrations from the database.
bool loadGraspDemonstrationsByObjectName (const std::string &object_name, std::vector< GraspDemonstration > &gds) const
 Load grasp demonstrations from the database from an object name.
bool loadGraspModel (uint32_t id, GraspModel &gm) const
 Load a grasp model from the database.
bool loadGraspModels (std::vector< GraspModel > &gms) const
 Load all grasp models from the database.
bool loadGraspModelsByObjectName (const std::string &object_name, std::vector< GraspModel > &gms) const
 Load grasp models from the database from an object name.
virtual ~Client ()
 Cleans up a Client.

Static Public Attributes

static const unsigned int DEFAULT_PORT = 5432

Private Member Functions

void checkAPIVersion () const
 Check for a supported version of the libpqxx API.
void createTables () const
 Creates tables and types.
bool doesTypeExist (const std::string &type) const
 Check if a composite type exists in the database.
std::vector< double > extractArrayFromString (std::string &array) const
 Extract array values from a string array with vector creation.
GraspDemonstration extractGraspDemonstrationFromTuple (const pqxx::result::tuple &tuple) const
 Extract grasp demonstration information from the SQL result tuple.
Grasp extractGraspFromTuple (const pqxx::result::tuple &tuple) const
 Extract grasp information from the SQL result tuple.
GraspModel extractGraspModelFromTuple (const pqxx::result::tuple &tuple) const
 Extract grasp model information from the SQL result tuple.
sensor_msgs::Image extractImageFromBinaryString (const pqxx::binarystring &bs) const
 Extract Image values from a binary string.
sensor_msgs::PointCloud2 extractPointCloud2FromBinaryString (const pqxx::binarystring &bs) const
 Extract PointCloud2 values from a binary string.
time_t extractTimeFromString (const std::string &str) const
 Extract a time from a timestamp.
bool getStringArrayFromPrepared (const std::string &prepared_name, const std::string &column_name, std::vector< std::string > &strings) const
 Extract a string column from the database.
std::string toSQL (const Pose &p) const
 Convert a Pose to a PostgreSQL object string.
std::string toSQL (const Position &p) const
 Convert a Position to a PostgreSQL object string.
std::string toSQL (const Orientation &o) const
 Convert an Orientation to a PostgreSQL object string.

Private Attributes

pqxx::connection * connection_
std::string db_
std::string host_
std::string password_
uint16_t port_
std::string user_

Detailed Description

The main grasp database client.

The graspdb client can communicate with a PostgreSQL database.

Definition at line 40 of file Client.h.


Constructor & Destructor Documentation

Client::Client ( const Client c)

Create a new Client.

Creates a new Client by copying the values from the given Client. A new connection is made if one exists.

Parameters:
gdThe Client to copy.

Definition at line 20 of file Client.cpp.

rail::pick_and_place::graspdb::Client::Client ( const std::string &  host,
const uint16_t  port,
const std::string &  user,
const std::string &  password,
const std::string &  db 
)

Create a new Client.

Creates a new Client with the given connection information. A connection is not made by default.

Parameters:
hostThe host IP of the database.
portThe host port of the database.
userThe user of the database.
passwordThe password for the user of the database.
dbThe database name.
Client::~Client ( ) [virtual]

Cleans up a Client.

Cleans up any connections used by the Client.

Definition at line 46 of file Client.cpp.


Member Function Documentation

bool Client::addGrasp ( Grasp graps) const

Add a grasp to the database.

Stores the given grasp data to the database. If the entity was successfully added, the ID and created fields of the Grasp are set accordingly.

Parameters:
gThe Grasp with the data to store.
Returns:
Returns true if the entity was added to the database.

Definition at line 441 of file Client.cpp.

Add a grasp demonstration to the database.

Stores the given grasp demonstration data to the database. If the grasp was successfully added, the ID and created fields of the GraspDemonstration are set accordingly.

Parameters:
gdThe GraspDemonstration with the data to store.
Returns:
True if the grasp was successfully added.

Definition at line 560 of file Client.cpp.

bool Client::addGraspModel ( GraspModel gm) const

Add a grasp model and its associated grasps to the database.

Stores the given grasp model data and its associated grasps to the database. If the entity was successfully added, the ID and created fields of the GraspModel are set accordingly.

Parameters:
gmThe GraspModel with the data to store.
Returns:
Returns true if the entity was added to the database.

Definition at line 554 of file Client.cpp.

void Client::checkAPIVersion ( ) const [private]

Check for a supported version of the libpqxx API.

Checks for a valid version of the libpqxx API (4.0.0 or greater). If one is not found an error message is printed to ROS_WARN. If a valid version is found during compile time, this function has no effect.

Definition at line 52 of file Client.cpp.

bool Client::connect ( )

Create a connection to the database.

Attempts to create a connection to the grasp database. A flag is returned to indicate the success.

Returns:
True if a connection has been sucessfully made.

Definition at line 90 of file Client.cpp.

bool Client::connected ( ) const

Check if there is a connection to the database.

A boolean check to see if a connection exists to the grasp database.

Returns:
True if a connection has been made.

Definition at line 85 of file Client.cpp.

void Client::createTables ( ) const [private]

Creates tables and types.

Creates the initial table and composite type schemas needed for the database. If these already exist, no action is taken.

Definition at line 174 of file Client.cpp.

void Client::deleteGrasp ( uint32_t  id) const

Delete a grasp from the database.

Deletes the grasp from the database with the given ID.

Parameters:
idThe ID of the grasp to delete.

Definition at line 568 of file Client.cpp.

void Client::deleteGraspDemonstration ( uint32_t  id) const

Delete a grasp demonstration from the database.

Deletes the grasp demonstration from the database with the given ID.

Parameters:
idThe ID of the grasp demonstration to delete.

Definition at line 576 of file Client.cpp.

void Client::deleteGraspModel ( uint32_t  id) const

Delete a grasp model from the database.

Deletes the grasp model from the database with the given ID. All associated grasps are also deleted.

Parameters:
idThe ID of the grasp model to delete.

Definition at line 584 of file Client.cpp.

Closes a connection to the database.

Attempts to close a connection to the grasp database. No effect is seen if there is no current connection.

Definition at line 160 of file Client.cpp.

bool Client::doesTypeExist ( const std::string &  type) const [private]

Check if a composite type exists in the database.

Makes an SQL call to the database to check if a composite type of the given name exists.

Parameters:
typeThe name of the type to check for.
Returns:
True if the type composite exists in the database.

Definition at line 228 of file Client.cpp.

vector< double > Client::extractArrayFromString ( std::string &  array) const [private]

Extract array values from a string array with vector creation.

Extracts double values from the given PostgreSQL array string (e.g., "{1,2,3}") and places them in a new vector.

Parameters:
arrayThe array string representation of the array.
Returns:
The vector to populated with values from the string.

Definition at line 702 of file Client.cpp.

GraspDemonstration Client::extractGraspDemonstrationFromTuple ( const pqxx::result::tuple &  tuple) const [private]

Extract grasp demonstration information from the SQL result tuple.

Extracts values from the given SQL result tuple and places them in a new GraspDemonstration object.

Parameters:
resultThe SQL result tuple containing the correct values.
Returns:
The GraspDemonstration populated with values from the SQL result tuple.

Definition at line 592 of file Client.cpp.

Grasp Client::extractGraspFromTuple ( const pqxx::result::tuple &  tuple) const [private]

Extract grasp information from the SQL result tuple.

Extracts values from the given SQL result tuple and places them in a new Grasp object.

Parameters:
resultThe SQL result tuple containing the correct values.
Returns:
The Grasp populated with values from the SQL result tuple.

Definition at line 634 of file Client.cpp.

GraspModel Client::extractGraspModelFromTuple ( const pqxx::result::tuple &  tuple) const [private]

Extract grasp model information from the SQL result tuple.

Extracts values from the given SQL result tuple and places them in a new GraspModel object.

Parameters:
resultThe SQL result tuple containing the correct values.
Returns:
The GraspModel populated with values from the SQL result tuple.

Definition at line 664 of file Client.cpp.

sensor_msgs::Image Client::extractImageFromBinaryString ( const pqxx::binarystring &  bs) const [private]

Extract Image values from a binary string.

Extracts Image values from the given PostgreSQL binary string and places them in a new ROS Image message.

Parameters:
bsThe binary string representation of the serialized Image.
Returns:
The Image with values from the binary string.

Definition at line 693 of file Client.cpp.

sensor_msgs::PointCloud2 Client::extractPointCloud2FromBinaryString ( const pqxx::binarystring &  bs) const [private]

Extract PointCloud2 values from a binary string.

Extracts PointCloud2 values from the given PostgreSQL binary string and places them in a new ROS PointCloud2 message.

Parameters:
bsThe binary string representation of the serialized PointCloud2.
Returns:
The PointCloud2 with values from the binary string.

Definition at line 684 of file Client.cpp.

time_t Client::extractTimeFromString ( const std::string &  str) const [private]

Extract a time from a timestamp.

Extracts a time value from the given PostgreSQL.

Parameters:
strThe timestamp to parse.
Returns:
The time value from the string.

Definition at line 727 of file Client.cpp.

const string & Client::getDatabase ( ) const

Database value accessor.

Get the database value of this Client.

Returns:
The database value.

Definition at line 80 of file Client.cpp.

const string & Client::getHost ( ) const

Host value accessor.

Get the host value of this Client.

Returns:
The host value.

Definition at line 65 of file Client.cpp.

const string & Client::getPassword ( ) const

Password value accessor.

Get the password value of this Client.

Returns:
The password value.

Definition at line 75 of file Client.cpp.

uint16_t Client::getPort ( ) const

Port value accessor.

Get the port value of this Client.

Returns:
The port value.

Definition at line 60 of file Client.cpp.

bool Client::getStringArrayFromPrepared ( const std::string &  prepared_name,
const std::string &  column_name,
std::vector< std::string > &  strings 
) const [private]

Extract a string column from the database.

Attempt to get an array of strings from a prepared statement based on a given column name in the result. This will call the named prepared statement and extract the values form the given column and place them in the given vector.

Parameters:
prepared_nameThe name of the prepared statement to execute.
column_nameThe column name to extract strings from.
stringsThe vector to fill with the values.
Returns:
bool Returns true if a successful load was completed and the data was set correctly.

Definition at line 745 of file Client.cpp.

bool Client::getUniqueGraspDemonstrationObjectNames ( std::vector< std::string > &  names) const

Load the unique demonstration object names from the database.

Load a list of the unique object names from the grasp demonstrations.

Parameters:
namesThe vector to fill with the unique names.
Returns:
bool Returns true if a successful load was completed and the data was set correctly.

Definition at line 431 of file Client.cpp.

bool Client::getUniqueGraspModelObjectNames ( std::vector< std::string > &  names) const

Load the unique grasp model object names from the database.

Load a list of the unique object names from the grasp models.

Parameters:
namesThe vector to fill with the unique names.
Returns:
bool Returns true if a successful load was completed and the data was set correctly.

Definition at line 436 of file Client.cpp.

const string & Client::getUser ( ) const

User value accessor.

Get the user value of this Client.

Returns:
The user value.

Definition at line 70 of file Client.cpp.

bool Client::loadGrasp ( uint32_t  id,
Grasp grasp 
) const

Load a grasp from the database.

Load the grasp data from the database with the given ID and store it in the given Grasp.

Parameters:
idThe ID of the grasp to load.
graspThe Grasp object to fill with the loaded data.
Returns:
bool Returns true if a successful load was completed and the data was set correctly.

Definition at line 301 of file Client.cpp.

bool Client::loadGraspByGraspModelID ( const uint32_t  grasp_model_id,
std::vector< Grasp > &  grasps 
) const

Load grasps from the database from an associated model ID.

Load the grasp data from the database with the given grasp model ID and store them in the given vector.

Parameters:
grasp_model_idThe object name of the grasp demonstrations to load.
graspsThe vector to fill with Grasp objects with the loaded data.
Returns:
bool Returns true if a successful load was completed and the data was set correctly.

Definition at line 320 of file Client.cpp.

bool Client::loadGraspDemonstration ( uint32_t  id,
GraspDemonstration gd 
) const

Load a grasp demonstration from the database.

Load the grasp demonstration data from the database with the given ID and store it in the given GraspDemonstration.

Parameters:
idThe ID of the grasp demonstration to load.
gdThe GraspDemonstration object to fill with the loaded data.
Returns:
bool Returns true if a successful load was completed and the data was set correctly.

Definition at line 238 of file Client.cpp.

bool Client::loadGraspDemonstrations ( std::vector< GraspDemonstration > &  gds) const

Load all grasp demonstrations from the database.

Load all grasp demonstrations data from the database with and store them in the given vector.

Parameters:
gdsThe vector to fill with GraspDemonstration objects with the loaded data.
Returns:
bool Returns true if a successful load was completed and the data was set correctly.

Definition at line 257 of file Client.cpp.

bool Client::loadGraspDemonstrationsByObjectName ( const std::string &  object_name,
std::vector< GraspDemonstration > &  gds 
) const

Load grasp demonstrations from the database from an object name.

Load the grasp demonstrations data from the database with the given object names and store them in the given vector.

Parameters:
object_nameThe object name of the grasp demonstrations to load.
gdsThe vector to fill with GraspDemonstration objects with the loaded data.
Returns:
bool Returns true if a successful load was completed and the data was set correctly.

Definition at line 279 of file Client.cpp.

bool Client::loadGraspModel ( uint32_t  id,
GraspModel gm 
) const

Load a grasp model from the database.

Load the grasp model data from the database with the given ID and store it in the given GraspModel. Associated grasps are also loaded.

Parameters:
idThe ID of the grasp model to load.
gmThe Grasp model object to fill with the loaded data.
Returns:
bool Returns true if a successful load was completed and the data was set correctly.

Definition at line 342 of file Client.cpp.

bool Client::loadGraspModels ( std::vector< GraspModel > &  gms) const

Load all grasp models from the database.

Load all grasp models data from the database and store them in the given vector.

Parameters:
gmsThe vector to fill with GraspModel objects with the loaded data.
Returns:
bool Returns true if a successful load was completed and the data was set correctly.

Definition at line 369 of file Client.cpp.

bool Client::loadGraspModelsByObjectName ( const std::string &  object_name,
std::vector< GraspModel > &  gms 
) const

Load grasp models from the database from an object name.

Load the grasp models data from the database with the given object names and store them in the given vector.

Parameters:
object_nameThe object name of the grasp model to load.
gmsThe vector to fill with GraspModel objects with the loaded data.
Returns:
bool Returns true if a successful load was completed and the data was set correctly.

Definition at line 400 of file Client.cpp.

string Client::toSQL ( const Pose p) const [private]

Convert a Pose to a PostgreSQL object string.

Converts the given Pose to a PostgreSQL object string for use in SQL queries.

Parameters:
pThe Pose object to convert to a PostgreSQL object string.
Returns:
The converted PostgreSQL object string.

Definition at line 768 of file Client.cpp.

string Client::toSQL ( const Position p) const [private]

Convert a Position to a PostgreSQL object string.

Converts the given Position to a PostgreSQL object string for use in SQL queries.

Parameters:
pThe Position object to convert to a PostgreSQL object string.
Returns:
The converted PostgreSQL object string.

Definition at line 776 of file Client.cpp.

string Client::toSQL ( const Orientation o) const [private]

Convert an Orientation to a PostgreSQL object string.

Converts the given Orientation to a PostgreSQL object string for use in SQL queries.

Parameters:
oThe Orientation object to convert to a PostgreSQL object string.
Returns:
The converted PostgreSQL object string.

Definition at line 784 of file Client.cpp.


Member Data Documentation

The main database connection client.

Definition at line 484 of file Client.h.

Definition at line 480 of file Client.h.

const unsigned int rail::pick_and_place::graspdb::Client::DEFAULT_PORT = 5432 [static]

The default PostgreSQL port.

Definition at line 44 of file Client.h.

Database connection information.

Definition at line 480 of file Client.h.

Definition at line 480 of file Client.h.

Database port information.

Definition at line 482 of file Client.h.

Definition at line 480 of file Client.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