database_grasp.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2009, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 // Author(s): Matei Ciocarlie
00036 
00037 #ifndef _DATABASE_GRASP_H_
00038 #define _DATABASE_GRASP_H_
00039 
00040 #include <iostream>
00041 
00042 #include <geometry_msgs/Pose.h>
00043 
00044 #include <database_interface/db_class.h>
00045 
00046 #include <boost/shared_ptr.hpp>
00047 
00048 #include "household_objects_database/database_helper_classes.h"
00049 
00050 namespace household_objects_database {
00051 
00052 /*
00053    For now we use the stored "energy" from the database as grasp quality; this is OK, though
00054    in the future we hope to have better measures. For now, this has the counterintuitive effect
00055    that lower values are better, which is what the term "energy" implies. However, in this
00056    class we use it as "quality" which usually means that higher is better.
00057  */
00058 
00060 class DatabaseGrasp : public database_interface::DBClass
00061 {
00062  private:
00063 
00064  public:
00066   database_interface::DBField<int> id_;
00068   database_interface::DBField<int> scaled_model_id_;
00069 
00071   database_interface::DBField<DatabasePose> pre_grasp_pose_;
00073   database_interface::DBField<DatabaseHandPosture> pre_grasp_posture_;
00074 
00076   database_interface::DBField<DatabasePose> final_grasp_pose_;
00078   database_interface::DBField<DatabaseHandPosture> final_grasp_posture_;
00079 
00081   database_interface::DBField<double> quality_;
00083   database_interface::DBField<double> pre_grasp_clearance_;
00085   database_interface::DBField<bool> cluster_rep_;
00087   database_interface::DBField<double> table_clearance_;
00088 
00090   database_interface::DBField<std::string> hand_name_;
00091 
00093   database_interface::DBField<bool> compliant_copy_;
00095   database_interface::DBField<int> compliant_original_id_;
00096 
00098   database_interface::DBField<double> scaled_quality_;
00099 
00100   database_interface::DBField<bool> fingertip_object_collision_;
00101 
00103   DatabaseGrasp() :
00104    id_(database_interface::DBFieldBase::TEXT, this, "grasp_id", "grasp", true),
00105    scaled_model_id_(database_interface::DBFieldBase::TEXT, this, "scaled_model_id", "grasp", true),
00106    pre_grasp_pose_(database_interface::DBFieldBase::TEXT, this, "grasp_pregrasp_position", "grasp", true),
00107    pre_grasp_posture_(database_interface::DBFieldBase::TEXT, this, "grasp_pregrasp_joints", "grasp", true),
00108    final_grasp_pose_(database_interface::DBFieldBase::TEXT, this, "grasp_grasp_position", "grasp", true),
00109    final_grasp_posture_(database_interface::DBFieldBase::TEXT, this, "grasp_grasp_joints", "grasp", true),
00110    quality_(database_interface::DBFieldBase::TEXT, this, "grasp_energy", "grasp", true),
00111    pre_grasp_clearance_(database_interface::DBFieldBase::TEXT, this, "grasp_pregrasp_clearance", "grasp", true),
00112    cluster_rep_(database_interface::DBFieldBase::TEXT, this, "grasp_cluster_rep", "grasp", true),
00113    table_clearance_(database_interface::DBFieldBase::TEXT, this, "grasp_table_clearance", "grasp", true),
00114    hand_name_(database_interface::DBFieldBase::TEXT, this, "hand_name", "grasp", true),
00115    compliant_copy_(database_interface::DBFieldBase::TEXT, this, "grasp_compliant_copy", "grasp", true),
00116    compliant_original_id_(database_interface::DBFieldBase::TEXT, this, "grasp_compliant_original_id", "grasp", true),
00117    scaled_quality_(database_interface::DBFieldBase::TEXT, this, "grasp_scaled_quality", "grasp", true),
00118    fingertip_object_collision_(database_interface::DBFieldBase::TEXT, this, "fingertip_object_collision", "grasp", true)
00119   {
00120     //primary key field
00121     primary_key_field_ = &id_;
00122     //all the other fields
00123     fields_.push_back(&scaled_model_id_);
00124     fields_.push_back(&pre_grasp_pose_);
00125     fields_.push_back(&pre_grasp_posture_);
00126     fields_.push_back(&final_grasp_pose_);
00127     fields_.push_back(&final_grasp_posture_);
00128     fields_.push_back(&quality_);
00129     fields_.push_back(&pre_grasp_clearance_);
00130     fields_.push_back(&cluster_rep_);
00131     fields_.push_back(&table_clearance_);
00132     fields_.push_back(&hand_name_);
00133     fields_.push_back(&compliant_copy_);
00134     fields_.push_back(&compliant_original_id_);
00135     fields_.push_back(&scaled_quality_);
00136     fields_.push_back(&fingertip_object_collision_);
00137 
00138     //sequences
00139     id_.setSequenceName("grasp_grasp_id_seq");
00140 
00141     //by default, all fields here are used, and many of then not-null, so sync both ways
00142     setAllFieldsReadFromDatabase(true);
00143     setAllFieldsWriteToDatabase(true);
00144     //primary key id_ only syncs from database; it has a sequence which is used by default on insertions
00145     id_.setWriteToDatabase(false);
00146   }
00147 
00149   ~DatabaseGrasp(){}
00150 };
00151 
00152 
00153 typedef boost::shared_ptr<DatabaseGrasp> DatabaseGraspPtr;
00154 
00155 } //namespace
00156 
00157 #endif


household_objects_database
Author(s): Matei Ciocarlie, except for source files individually marked otherwise
autogenerated on Thu Jan 2 2014 11:40:12