00001
00002 #ifndef SRS_OBJECT_DATABASE_MSGS_SERVICE_INSERTOBJECT_H
00003 #define SRS_OBJECT_DATABASE_MSGS_SERVICE_INSERTOBJECT_H
00004 #include <string>
00005 #include <vector>
00006 #include <map>
00007 #include <ostream>
00008 #include "ros/serialization.h"
00009 #include "ros/builtin_message_traits.h"
00010 #include "ros/message_operations.h"
00011 #include "ros/time.h"
00012
00013 #include "ros/macros.h"
00014
00015 #include "ros/assert.h"
00016
00017 #include "ros/service_traits.h"
00018
00019 #include "sensor_msgs/Image.h"
00020
00021
00022
00023 namespace srs_object_database_msgs
00024 {
00025 template <class ContainerAllocator>
00026 struct InsertObjectRequest_ {
00027 typedef InsertObjectRequest_<ContainerAllocator> Type;
00028
00029 InsertObjectRequest_()
00030 : function()
00031 , model_id(0)
00032 , model_name()
00033 , model_desc()
00034 , model_category()
00035 , model_x_size(0.0)
00036 , model_y_size(0.0)
00037 , model_z_size(0.0)
00038 , model_basic_shape()
00039 , graspable(false)
00040 , pcl()
00041 , fpt()
00042 , img()
00043 , image_type()
00044 , data_grasp()
00045 , data_mesh()
00046 , meshType()
00047 , urdf()
00048 {
00049 }
00050
00051 InsertObjectRequest_(const ContainerAllocator& _alloc)
00052 : function(_alloc)
00053 , model_id(0)
00054 , model_name(_alloc)
00055 , model_desc(_alloc)
00056 , model_category(_alloc)
00057 , model_x_size(0.0)
00058 , model_y_size(0.0)
00059 , model_z_size(0.0)
00060 , model_basic_shape(_alloc)
00061 , graspable(false)
00062 , pcl(_alloc)
00063 , fpt(_alloc)
00064 , img(_alloc)
00065 , image_type(_alloc)
00066 , data_grasp(_alloc)
00067 , data_mesh(_alloc)
00068 , meshType(_alloc)
00069 , urdf(_alloc)
00070 {
00071 }
00072
00073 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _function_type;
00074 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > function;
00075
00076 typedef int32_t _model_id_type;
00077 int32_t model_id;
00078
00079 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _model_name_type;
00080 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > model_name;
00081
00082 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _model_desc_type;
00083 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > model_desc;
00084
00085 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _model_category_type;
00086 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > model_category;
00087
00088 typedef float _model_x_size_type;
00089 float model_x_size;
00090
00091 typedef float _model_y_size_type;
00092 float model_y_size;
00093
00094 typedef float _model_z_size_type;
00095 float model_z_size;
00096
00097 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _model_basic_shape_type;
00098 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > model_basic_shape;
00099
00100 typedef uint8_t _graspable_type;
00101 uint8_t graspable;
00102
00103 typedef std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other > _pcl_type;
00104 std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other > pcl;
00105
00106 typedef std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other > _fpt_type;
00107 std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other > fpt;
00108
00109 typedef ::sensor_msgs::Image_<ContainerAllocator> _img_type;
00110 ::sensor_msgs::Image_<ContainerAllocator> img;
00111
00112 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _image_type_type;
00113 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > image_type;
00114
00115 typedef std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other > _data_grasp_type;
00116 std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other > data_grasp;
00117
00118 typedef std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other > _data_mesh_type;
00119 std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other > data_mesh;
00120
00121 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _meshType_type;
00122 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > meshType;
00123
00124 typedef std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other > _urdf_type;
00125 std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other > urdf;
00126
00127
00128 typedef boost::shared_ptr< ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> > Ptr;
00129 typedef boost::shared_ptr< ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> const> ConstPtr;
00130 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00131 };
00132 typedef ::srs_object_database_msgs::InsertObjectRequest_<std::allocator<void> > InsertObjectRequest;
00133
00134 typedef boost::shared_ptr< ::srs_object_database_msgs::InsertObjectRequest> InsertObjectRequestPtr;
00135 typedef boost::shared_ptr< ::srs_object_database_msgs::InsertObjectRequest const> InsertObjectRequestConstPtr;
00136
00137
00138
00139 template <class ContainerAllocator>
00140 struct InsertObjectResponse_ {
00141 typedef InsertObjectResponse_<ContainerAllocator> Type;
00142
00143 InsertObjectResponse_()
00144 : return_response()
00145 , model_id(0)
00146 {
00147 }
00148
00149 InsertObjectResponse_(const ContainerAllocator& _alloc)
00150 : return_response(_alloc)
00151 , model_id(0)
00152 {
00153 }
00154
00155 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _return_response_type;
00156 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > return_response;
00157
00158 typedef int32_t _model_id_type;
00159 int32_t model_id;
00160
00161
00162 typedef boost::shared_ptr< ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> > Ptr;
00163 typedef boost::shared_ptr< ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> const> ConstPtr;
00164 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00165 };
00166 typedef ::srs_object_database_msgs::InsertObjectResponse_<std::allocator<void> > InsertObjectResponse;
00167
00168 typedef boost::shared_ptr< ::srs_object_database_msgs::InsertObjectResponse> InsertObjectResponsePtr;
00169 typedef boost::shared_ptr< ::srs_object_database_msgs::InsertObjectResponse const> InsertObjectResponseConstPtr;
00170
00171
00172 struct InsertObject
00173 {
00174
00175 typedef InsertObjectRequest Request;
00176 typedef InsertObjectResponse Response;
00177 Request request;
00178 Response response;
00179
00180 typedef Request RequestType;
00181 typedef Response ResponseType;
00182 };
00183 }
00184
00185 namespace ros
00186 {
00187 namespace message_traits
00188 {
00189 template<class ContainerAllocator> struct IsMessage< ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> > : public TrueType {};
00190 template<class ContainerAllocator> struct IsMessage< ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> const> : public TrueType {};
00191 template<class ContainerAllocator>
00192 struct MD5Sum< ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> > {
00193 static const char* value()
00194 {
00195 return "4045f8a3a36be31cf6b0274a21ca2bb4";
00196 }
00197
00198 static const char* value(const ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> &) { return value(); }
00199 static const uint64_t static_value1 = 0x4045f8a3a36be31cULL;
00200 static const uint64_t static_value2 = 0xf6b0274a21ca2bb4ULL;
00201 };
00202
00203 template<class ContainerAllocator>
00204 struct DataType< ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> > {
00205 static const char* value()
00206 {
00207 return "srs_object_database_msgs/InsertObjectRequest";
00208 }
00209
00210 static const char* value(const ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> &) { return value(); }
00211 };
00212
00213 template<class ContainerAllocator>
00214 struct Definition< ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> > {
00215 static const char* value()
00216 {
00217 return "\n\
00218 \n\
00219 \n\
00220 \n\
00221 string function\n\
00222 \n\
00223 \n\
00224 int32 model_id\n\
00225 \n\
00226 \n\
00227 string model_name\n\
00228 \n\
00229 \n\
00230 string model_desc\n\
00231 \n\
00232 \n\
00233 string model_category\n\
00234 \n\
00235 \n\
00236 float32 model_x_size\n\
00237 \n\
00238 \n\
00239 float32 model_y_size\n\
00240 \n\
00241 \n\
00242 float32 model_z_size\n\
00243 \n\
00244 \n\
00245 string model_basic_shape\n\
00246 \n\
00247 \n\
00248 bool graspable\n\
00249 \n\
00250 \n\
00251 \n\
00252 uint8[] pcl\n\
00253 uint8[] fpt\n\
00254 sensor_msgs/Image img\n\
00255 string image_type\n\
00256 uint8[] data_grasp\n\
00257 \n\
00258 uint8[] data_mesh\n\
00259 string meshType\n\
00260 uint8[] urdf\n\
00261 \n\
00262 \n\
00263 ================================================================================\n\
00264 MSG: sensor_msgs/Image\n\
00265 # This message contains an uncompressed image\n\
00266 # (0, 0) is at top-left corner of image\n\
00267 #\n\
00268 \n\
00269 Header header # Header timestamp should be acquisition time of image\n\
00270 # Header frame_id should be optical frame of camera\n\
00271 # origin of frame should be optical center of cameara\n\
00272 # +x should point to the right in the image\n\
00273 # +y should point down in the image\n\
00274 # +z should point into to plane of the image\n\
00275 # If the frame_id here and the frame_id of the CameraInfo\n\
00276 # message associated with the image conflict\n\
00277 # the behavior is undefined\n\
00278 \n\
00279 uint32 height # image height, that is, number of rows\n\
00280 uint32 width # image width, that is, number of columns\n\
00281 \n\
00282 # The legal values for encoding are in file src/image_encodings.cpp\n\
00283 # If you want to standardize a new string format, join\n\
00284 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.\n\
00285 \n\
00286 string encoding # Encoding of pixels -- channel meaning, ordering, size\n\
00287 # taken from the list of strings in include/sensor_msgs/image_encodings.h\n\
00288 \n\
00289 uint8 is_bigendian # is this data bigendian?\n\
00290 uint32 step # Full row length in bytes\n\
00291 uint8[] data # actual matrix data, size is (step * rows)\n\
00292 \n\
00293 ================================================================================\n\
00294 MSG: std_msgs/Header\n\
00295 # Standard metadata for higher-level stamped data types.\n\
00296 # This is generally used to communicate timestamped data \n\
00297 # in a particular coordinate frame.\n\
00298 # \n\
00299 # sequence ID: consecutively increasing ID \n\
00300 uint32 seq\n\
00301 #Two-integer timestamp that is expressed as:\n\
00302 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00303 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00304 # time-handling sugar is provided by the client library\n\
00305 time stamp\n\
00306 #Frame this data is associated with\n\
00307 # 0: no frame\n\
00308 # 1: global frame\n\
00309 string frame_id\n\
00310 \n\
00311 ";
00312 }
00313
00314 static const char* value(const ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> &) { return value(); }
00315 };
00316
00317 }
00318 }
00319
00320
00321 namespace ros
00322 {
00323 namespace message_traits
00324 {
00325 template<class ContainerAllocator> struct IsMessage< ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> > : public TrueType {};
00326 template<class ContainerAllocator> struct IsMessage< ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> const> : public TrueType {};
00327 template<class ContainerAllocator>
00328 struct MD5Sum< ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> > {
00329 static const char* value()
00330 {
00331 return "bcd4a8cb19bdcae33e0a74fc2d3b2e46";
00332 }
00333
00334 static const char* value(const ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> &) { return value(); }
00335 static const uint64_t static_value1 = 0xbcd4a8cb19bdcae3ULL;
00336 static const uint64_t static_value2 = 0x3e0a74fc2d3b2e46ULL;
00337 };
00338
00339 template<class ContainerAllocator>
00340 struct DataType< ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> > {
00341 static const char* value()
00342 {
00343 return "srs_object_database_msgs/InsertObjectResponse";
00344 }
00345
00346 static const char* value(const ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> &) { return value(); }
00347 };
00348
00349 template<class ContainerAllocator>
00350 struct Definition< ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> > {
00351 static const char* value()
00352 {
00353 return "\n\
00354 \n\
00355 string return_response\n\
00356 \n\
00357 int32 model_id\n\
00358 \n\
00359 \n\
00360 \n\
00361 ";
00362 }
00363
00364 static const char* value(const ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> &) { return value(); }
00365 };
00366
00367 }
00368 }
00369
00370 namespace ros
00371 {
00372 namespace serialization
00373 {
00374
00375 template<class ContainerAllocator> struct Serializer< ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> >
00376 {
00377 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00378 {
00379 stream.next(m.function);
00380 stream.next(m.model_id);
00381 stream.next(m.model_name);
00382 stream.next(m.model_desc);
00383 stream.next(m.model_category);
00384 stream.next(m.model_x_size);
00385 stream.next(m.model_y_size);
00386 stream.next(m.model_z_size);
00387 stream.next(m.model_basic_shape);
00388 stream.next(m.graspable);
00389 stream.next(m.pcl);
00390 stream.next(m.fpt);
00391 stream.next(m.img);
00392 stream.next(m.image_type);
00393 stream.next(m.data_grasp);
00394 stream.next(m.data_mesh);
00395 stream.next(m.meshType);
00396 stream.next(m.urdf);
00397 }
00398
00399 ROS_DECLARE_ALLINONE_SERIALIZER;
00400 };
00401 }
00402 }
00403
00404
00405 namespace ros
00406 {
00407 namespace serialization
00408 {
00409
00410 template<class ContainerAllocator> struct Serializer< ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> >
00411 {
00412 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00413 {
00414 stream.next(m.return_response);
00415 stream.next(m.model_id);
00416 }
00417
00418 ROS_DECLARE_ALLINONE_SERIALIZER;
00419 };
00420 }
00421 }
00422
00423 namespace ros
00424 {
00425 namespace service_traits
00426 {
00427 template<>
00428 struct MD5Sum<srs_object_database_msgs::InsertObject> {
00429 static const char* value()
00430 {
00431 return "665c5bed07e3c52611345e1782e947e1";
00432 }
00433
00434 static const char* value(const srs_object_database_msgs::InsertObject&) { return value(); }
00435 };
00436
00437 template<>
00438 struct DataType<srs_object_database_msgs::InsertObject> {
00439 static const char* value()
00440 {
00441 return "srs_object_database_msgs/InsertObject";
00442 }
00443
00444 static const char* value(const srs_object_database_msgs::InsertObject&) { return value(); }
00445 };
00446
00447 template<class ContainerAllocator>
00448 struct MD5Sum<srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> > {
00449 static const char* value()
00450 {
00451 return "665c5bed07e3c52611345e1782e947e1";
00452 }
00453
00454 static const char* value(const srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> &) { return value(); }
00455 };
00456
00457 template<class ContainerAllocator>
00458 struct DataType<srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> > {
00459 static const char* value()
00460 {
00461 return "srs_object_database_msgs/InsertObject";
00462 }
00463
00464 static const char* value(const srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> &) { return value(); }
00465 };
00466
00467 template<class ContainerAllocator>
00468 struct MD5Sum<srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> > {
00469 static const char* value()
00470 {
00471 return "665c5bed07e3c52611345e1782e947e1";
00472 }
00473
00474 static const char* value(const srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> &) { return value(); }
00475 };
00476
00477 template<class ContainerAllocator>
00478 struct DataType<srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> > {
00479 static const char* value()
00480 {
00481 return "srs_object_database_msgs/InsertObject";
00482 }
00483
00484 static const char* value(const srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> &) { return value(); }
00485 };
00486
00487 }
00488 }
00489
00490 #endif // SRS_OBJECT_DATABASE_MSGS_SERVICE_INSERTOBJECT_H
00491