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 template <class ContainerAllocator>
00139 struct InsertObjectResponse_ {
00140 typedef InsertObjectResponse_<ContainerAllocator> Type;
00141
00142 InsertObjectResponse_()
00143 : return_response()
00144 , model_id(0)
00145 {
00146 }
00147
00148 InsertObjectResponse_(const ContainerAllocator& _alloc)
00149 : return_response(_alloc)
00150 , model_id(0)
00151 {
00152 }
00153
00154 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _return_response_type;
00155 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > return_response;
00156
00157 typedef int32_t _model_id_type;
00158 int32_t model_id;
00159
00160
00161 typedef boost::shared_ptr< ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> > Ptr;
00162 typedef boost::shared_ptr< ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> const> ConstPtr;
00163 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00164 };
00165 typedef ::srs_object_database_msgs::InsertObjectResponse_<std::allocator<void> > InsertObjectResponse;
00166
00167 typedef boost::shared_ptr< ::srs_object_database_msgs::InsertObjectResponse> InsertObjectResponsePtr;
00168 typedef boost::shared_ptr< ::srs_object_database_msgs::InsertObjectResponse const> InsertObjectResponseConstPtr;
00169
00170 struct InsertObject
00171 {
00172
00173 typedef InsertObjectRequest Request;
00174 typedef InsertObjectResponse Response;
00175 Request request;
00176 Response response;
00177
00178 typedef Request RequestType;
00179 typedef Response ResponseType;
00180 };
00181 }
00182
00183 namespace ros
00184 {
00185 namespace message_traits
00186 {
00187 template<class ContainerAllocator> struct IsMessage< ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> > : public TrueType {};
00188 template<class ContainerAllocator> struct IsMessage< ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> const> : public TrueType {};
00189 template<class ContainerAllocator>
00190 struct MD5Sum< ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> > {
00191 static const char* value()
00192 {
00193 return "4045f8a3a36be31cf6b0274a21ca2bb4";
00194 }
00195
00196 static const char* value(const ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> &) { return value(); }
00197 static const uint64_t static_value1 = 0x4045f8a3a36be31cULL;
00198 static const uint64_t static_value2 = 0xf6b0274a21ca2bb4ULL;
00199 };
00200
00201 template<class ContainerAllocator>
00202 struct DataType< ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> > {
00203 static const char* value()
00204 {
00205 return "srs_object_database_msgs/InsertObjectRequest";
00206 }
00207
00208 static const char* value(const ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> &) { return value(); }
00209 };
00210
00211 template<class ContainerAllocator>
00212 struct Definition< ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> > {
00213 static const char* value()
00214 {
00215 return "\n\
00216 \n\
00217 \n\
00218 \n\
00219 string function\n\
00220 \n\
00221 \n\
00222 int32 model_id\n\
00223 \n\
00224 \n\
00225 string model_name\n\
00226 \n\
00227 \n\
00228 string model_desc\n\
00229 \n\
00230 \n\
00231 string model_category\n\
00232 \n\
00233 \n\
00234 float32 model_x_size\n\
00235 \n\
00236 \n\
00237 float32 model_y_size\n\
00238 \n\
00239 \n\
00240 float32 model_z_size\n\
00241 \n\
00242 \n\
00243 string model_basic_shape\n\
00244 \n\
00245 \n\
00246 bool graspable\n\
00247 \n\
00248 \n\
00249 \n\
00250 uint8[] pcl\n\
00251 uint8[] fpt\n\
00252 sensor_msgs/Image img\n\
00253 string image_type\n\
00254 uint8[] data_grasp\n\
00255 \n\
00256 uint8[] data_mesh\n\
00257 string meshType\n\
00258 uint8[] urdf\n\
00259 \n\
00260 \n\
00261 ================================================================================\n\
00262 MSG: sensor_msgs/Image\n\
00263 # This message contains an uncompressed image\n\
00264 # (0, 0) is at top-left corner of image\n\
00265 #\n\
00266 \n\
00267 Header header # Header timestamp should be acquisition time of image\n\
00268 # Header frame_id should be optical frame of camera\n\
00269 # origin of frame should be optical center of cameara\n\
00270 # +x should point to the right in the image\n\
00271 # +y should point down in the image\n\
00272 # +z should point into to plane of the image\n\
00273 # If the frame_id here and the frame_id of the CameraInfo\n\
00274 # message associated with the image conflict\n\
00275 # the behavior is undefined\n\
00276 \n\
00277 uint32 height # image height, that is, number of rows\n\
00278 uint32 width # image width, that is, number of columns\n\
00279 \n\
00280 # The legal values for encoding are in file src/image_encodings.cpp\n\
00281 # If you want to standardize a new string format, join\n\
00282 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.\n\
00283 \n\
00284 string encoding # Encoding of pixels -- channel meaning, ordering, size\n\
00285 # taken from the list of strings in src/image_encodings.cpp\n\
00286 \n\
00287 uint8 is_bigendian # is this data bigendian?\n\
00288 uint32 step # Full row length in bytes\n\
00289 uint8[] data # actual matrix data, size is (step * rows)\n\
00290 \n\
00291 ================================================================================\n\
00292 MSG: std_msgs/Header\n\
00293 # Standard metadata for higher-level stamped data types.\n\
00294 # This is generally used to communicate timestamped data \n\
00295 # in a particular coordinate frame.\n\
00296 # \n\
00297 # sequence ID: consecutively increasing ID \n\
00298 uint32 seq\n\
00299 #Two-integer timestamp that is expressed as:\n\
00300 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00301 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00302 # time-handling sugar is provided by the client library\n\
00303 time stamp\n\
00304 #Frame this data is associated with\n\
00305 # 0: no frame\n\
00306 # 1: global frame\n\
00307 string frame_id\n\
00308 \n\
00309 ";
00310 }
00311
00312 static const char* value(const ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> &) { return value(); }
00313 };
00314
00315 }
00316 }
00317
00318
00319 namespace ros
00320 {
00321 namespace message_traits
00322 {
00323 template<class ContainerAllocator> struct IsMessage< ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> > : public TrueType {};
00324 template<class ContainerAllocator> struct IsMessage< ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> const> : public TrueType {};
00325 template<class ContainerAllocator>
00326 struct MD5Sum< ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> > {
00327 static const char* value()
00328 {
00329 return "bcd4a8cb19bdcae33e0a74fc2d3b2e46";
00330 }
00331
00332 static const char* value(const ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> &) { return value(); }
00333 static const uint64_t static_value1 = 0xbcd4a8cb19bdcae3ULL;
00334 static const uint64_t static_value2 = 0x3e0a74fc2d3b2e46ULL;
00335 };
00336
00337 template<class ContainerAllocator>
00338 struct DataType< ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> > {
00339 static const char* value()
00340 {
00341 return "srs_object_database_msgs/InsertObjectResponse";
00342 }
00343
00344 static const char* value(const ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> &) { return value(); }
00345 };
00346
00347 template<class ContainerAllocator>
00348 struct Definition< ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> > {
00349 static const char* value()
00350 {
00351 return "\n\
00352 \n\
00353 string return_response\n\
00354 \n\
00355 int32 model_id\n\
00356 \n\
00357 \n\
00358 \n\
00359 ";
00360 }
00361
00362 static const char* value(const ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> &) { return value(); }
00363 };
00364
00365 }
00366 }
00367
00368 namespace ros
00369 {
00370 namespace serialization
00371 {
00372
00373 template<class ContainerAllocator> struct Serializer< ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> >
00374 {
00375 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00376 {
00377 stream.next(m.function);
00378 stream.next(m.model_id);
00379 stream.next(m.model_name);
00380 stream.next(m.model_desc);
00381 stream.next(m.model_category);
00382 stream.next(m.model_x_size);
00383 stream.next(m.model_y_size);
00384 stream.next(m.model_z_size);
00385 stream.next(m.model_basic_shape);
00386 stream.next(m.graspable);
00387 stream.next(m.pcl);
00388 stream.next(m.fpt);
00389 stream.next(m.img);
00390 stream.next(m.image_type);
00391 stream.next(m.data_grasp);
00392 stream.next(m.data_mesh);
00393 stream.next(m.meshType);
00394 stream.next(m.urdf);
00395 }
00396
00397 ROS_DECLARE_ALLINONE_SERIALIZER;
00398 };
00399 }
00400 }
00401
00402
00403 namespace ros
00404 {
00405 namespace serialization
00406 {
00407
00408 template<class ContainerAllocator> struct Serializer< ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> >
00409 {
00410 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00411 {
00412 stream.next(m.return_response);
00413 stream.next(m.model_id);
00414 }
00415
00416 ROS_DECLARE_ALLINONE_SERIALIZER;
00417 };
00418 }
00419 }
00420
00421 namespace ros
00422 {
00423 namespace service_traits
00424 {
00425 template<>
00426 struct MD5Sum<srs_object_database_msgs::InsertObject> {
00427 static const char* value()
00428 {
00429 return "665c5bed07e3c52611345e1782e947e1";
00430 }
00431
00432 static const char* value(const srs_object_database_msgs::InsertObject&) { return value(); }
00433 };
00434
00435 template<>
00436 struct DataType<srs_object_database_msgs::InsertObject> {
00437 static const char* value()
00438 {
00439 return "srs_object_database_msgs/InsertObject";
00440 }
00441
00442 static const char* value(const srs_object_database_msgs::InsertObject&) { return value(); }
00443 };
00444
00445 template<class ContainerAllocator>
00446 struct MD5Sum<srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> > {
00447 static const char* value()
00448 {
00449 return "665c5bed07e3c52611345e1782e947e1";
00450 }
00451
00452 static const char* value(const srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> &) { return value(); }
00453 };
00454
00455 template<class ContainerAllocator>
00456 struct DataType<srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> > {
00457 static const char* value()
00458 {
00459 return "srs_object_database_msgs/InsertObject";
00460 }
00461
00462 static const char* value(const srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> &) { return value(); }
00463 };
00464
00465 template<class ContainerAllocator>
00466 struct MD5Sum<srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> > {
00467 static const char* value()
00468 {
00469 return "665c5bed07e3c52611345e1782e947e1";
00470 }
00471
00472 static const char* value(const srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> &) { return value(); }
00473 };
00474
00475 template<class ContainerAllocator>
00476 struct DataType<srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> > {
00477 static const char* value()
00478 {
00479 return "srs_object_database_msgs/InsertObject";
00480 }
00481
00482 static const char* value(const srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> &) { return value(); }
00483 };
00484
00485 }
00486 }
00487
00488 #endif // SRS_OBJECT_DATABASE_MSGS_SERVICE_INSERTOBJECT_H
00489