00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef _DATABASE_OBJECT_PATHS_H_
00038 #define _DATABASE_OBJECT_PATHS_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
00053 class DatabaseObjectPaths : public database_interface::DBClass
00054 {
00055 private:
00056
00057 public:
00059 database_interface::DBField<int> id_;
00060
00062 database_interface::DBField<int> scaled_model_id_;
00063
00064 database_interface::DBField<int> object_db_id_;
00065
00067 database_interface::DBField<std::string> object_description_;
00069 database_interface::DBField<std::string> object_geometry_hash_;
00071 database_interface::DBField<std::string> robot_geometry_hash_;
00072
00074 database_interface::DBField<double> hand_object_coefficient_of_friction_;
00076 database_interface::DBField<double> pushing_distance_;
00078 database_interface::DBField<double> in_hand_distance_;
00079
00081 database_interface::DBField<double> y_resolution_;
00083 database_interface::DBField<double> start_y_offset_;
00085 database_interface::DBField<int> n_y_steps_;
00086
00088 database_interface::DBField<double> rotation_resolution_;
00090 database_interface::DBField<int> n_rotations_;
00091
00093 database_interface::DBField< std::vector< std::vector< std::vector< std::vector< int > > > > > motion_types_;
00094
00096 database_interface::DBField< std::vector< std::vector< std::vector< std::vector< DatabasePose > > > > > poses_;
00097
00099 database_interface::DBField< std::vector< std::vector< std::vector< int > > > > path_lengths_;
00100
00101
00103 database_interface::DBField<double> radius_of_cylinder_bounding_the_object_;
00105 database_interface::DBField<DatabasePose> object_pushing_frame_in_object_frame_;
00106
00108 database_interface::DBField<double> fingertip_frame_to_pushing_surface_distance_;
00110 database_interface::DBField<double> finger_width_;
00111
00113 database_interface::DBField<double> aperture_width_;
00114
00116 database_interface::DBField<double> min_pressure_distribution_scale_;
00118 database_interface::DBField<double> max_pressure_distribution_scale_;
00120 database_interface::DBField<double> pressure_distribution_scale_resolution_;
00122 database_interface::DBField<int> n_pressure_distributions_;
00123
00125 database_interface::DBField<double> path_storage_resolution_;
00126
00127
00129 DatabaseObjectPaths() :
00130 id_(database_interface::DBFieldBase::TEXT, this, "object_paths_id", "object_paths", true),
00131 scaled_model_id_(database_interface::DBFieldBase::TEXT, this, "scaled_model_id", "object_paths", true),
00132 object_db_id_(database_interface::DBFieldBase::TEXT, this, "object_db_id", "object_paths", true),
00133 object_description_(database_interface::DBFieldBase::TEXT, this, "object_description", "object_paths", true),
00134 object_geometry_hash_(database_interface::DBFieldBase::TEXT, this, "object_geometry_hash", "object_paths", true),
00135 robot_geometry_hash_(database_interface::DBFieldBase::TEXT, this, "robot_geometry_hash", "object_paths", true),
00136 hand_object_coefficient_of_friction_(database_interface::DBFieldBase::TEXT, this, "hand_object_coefficient_of_friction", "object_paths", true),
00137 pushing_distance_(database_interface::DBFieldBase::TEXT, this, "pushing_distance", "object_paths", true),
00138 in_hand_distance_(database_interface::DBFieldBase::TEXT, this, "in_hand_distance", "object_paths", true),
00139 y_resolution_(database_interface::DBFieldBase::TEXT, this, "y_resolution", "object_paths", true),
00140 start_y_offset_(database_interface::DBFieldBase::TEXT, this, "start_y_offset", "object_paths", true),
00141 n_y_steps_(database_interface::DBFieldBase::TEXT, this, "n_y_steps", "object_paths", true),
00142 rotation_resolution_(database_interface::DBFieldBase::TEXT, this, "rotation_resolution", "object_paths", true),
00143 n_rotations_(database_interface::DBFieldBase::TEXT, this, "n_rotations", "object_paths", true),
00144 motion_types_(database_interface::DBFieldBase::TEXT, this, "motion_types", "object_paths", true),
00145 poses_(database_interface::DBFieldBase::TEXT, this, "poses", "object_paths", true),
00146 path_lengths_(database_interface::DBFieldBase::TEXT, this, "path_lengths", "object_paths", true),
00147 radius_of_cylinder_bounding_the_object_(database_interface::DBFieldBase::TEXT, this, "radius_of_cylinder_bounding_the_object", "object_paths", true),
00148 object_pushing_frame_in_object_frame_(database_interface::DBFieldBase::TEXT, this, "object_pushing_frame_in_object_frame", "object_paths", true),
00149 fingertip_frame_to_pushing_surface_distance_(database_interface::DBFieldBase::TEXT, this, "fingertip_frame_to_pushing_surface_distance", "object_paths", true),
00150 finger_width_(database_interface::DBFieldBase::TEXT, this, "finger_width", "object_paths", true),
00151 aperture_width_(database_interface::DBFieldBase::TEXT, this, "aperture_width", "object_paths", true),
00152 min_pressure_distribution_scale_(database_interface::DBFieldBase::TEXT, this, "min_pressure_distribution_scale", "object_paths", true),
00153 max_pressure_distribution_scale_(database_interface::DBFieldBase::TEXT, this, "max_pressure_distribution_scale", "object_paths", true),
00154 pressure_distribution_scale_resolution_(database_interface::DBFieldBase::TEXT, this, "pressure_distribution_scale_resolution", "object_paths", true),
00155 n_pressure_distributions_(database_interface::DBFieldBase::TEXT, this, "n_pressure_distributions", "object_paths", true),
00156 path_storage_resolution_(database_interface::DBFieldBase::TEXT, this, "path_storage_resolution", "object_paths", true)
00157 {
00158
00159 primary_key_field_ = &id_;
00160
00161 fields_.push_back(&scaled_model_id_);
00162 fields_.push_back(&object_db_id_);
00163 fields_.push_back(&object_description_);
00164 fields_.push_back(&object_geometry_hash_);
00165 fields_.push_back(&robot_geometry_hash_);
00166 fields_.push_back(&hand_object_coefficient_of_friction_);
00167 fields_.push_back(&pushing_distance_);
00168 fields_.push_back(&in_hand_distance_);
00169 fields_.push_back(&y_resolution_);
00170 fields_.push_back(&start_y_offset_);
00171 fields_.push_back(&n_y_steps_);
00172 fields_.push_back(&rotation_resolution_);
00173 fields_.push_back(&n_rotations_);
00174 fields_.push_back(&motion_types_);
00175 fields_.push_back(&poses_);
00176 fields_.push_back(&path_lengths_);
00177 fields_.push_back(&radius_of_cylinder_bounding_the_object_);
00178 fields_.push_back(&object_pushing_frame_in_object_frame_);
00179 fields_.push_back(&fingertip_frame_to_pushing_surface_distance_);
00180 fields_.push_back(&finger_width_);
00181 fields_.push_back(&aperture_width_);
00182 fields_.push_back(&min_pressure_distribution_scale_);
00183 fields_.push_back(&max_pressure_distribution_scale_);
00184 fields_.push_back(&pressure_distribution_scale_resolution_);
00185 fields_.push_back(&n_pressure_distributions_);
00186 fields_.push_back(&path_storage_resolution_);
00187
00188
00189 id_.setSequenceName("object_paths_id_seq");
00190
00191
00192 setAllFieldsReadFromDatabase(true);
00193 setAllFieldsWriteToDatabase(true);
00194
00195 id_.setWriteToDatabase(false);
00196 }
00197
00199 ~DatabaseObjectPaths(){}
00200 };
00201
00202 typedef boost::shared_ptr<DatabaseObjectPaths> DatabaseObjectPathsPtr;
00203
00204 }
00205
00206 #endif