$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-srs_common/doc_stacks/2013-03-02_13-44-44.967682/srs_common/srs_object_database_msgs/srv/InsertObject.srv */ 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 ROS_DEPRECATED uint32_t get_pcl_size() const { return (uint32_t)pcl.size(); } 00129 ROS_DEPRECATED void set_pcl_size(uint32_t size) { pcl.resize((size_t)size); } 00130 ROS_DEPRECATED void get_pcl_vec(std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other > & vec) const { vec = this->pcl; } 00131 ROS_DEPRECATED void set_pcl_vec(const std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other > & vec) { this->pcl = vec; } 00132 ROS_DEPRECATED uint32_t get_fpt_size() const { return (uint32_t)fpt.size(); } 00133 ROS_DEPRECATED void set_fpt_size(uint32_t size) { fpt.resize((size_t)size); } 00134 ROS_DEPRECATED void get_fpt_vec(std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other > & vec) const { vec = this->fpt; } 00135 ROS_DEPRECATED void set_fpt_vec(const std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other > & vec) { this->fpt = vec; } 00136 ROS_DEPRECATED uint32_t get_data_grasp_size() const { return (uint32_t)data_grasp.size(); } 00137 ROS_DEPRECATED void set_data_grasp_size(uint32_t size) { data_grasp.resize((size_t)size); } 00138 ROS_DEPRECATED void get_data_grasp_vec(std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other > & vec) const { vec = this->data_grasp; } 00139 ROS_DEPRECATED void set_data_grasp_vec(const std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other > & vec) { this->data_grasp = vec; } 00140 ROS_DEPRECATED uint32_t get_data_mesh_size() const { return (uint32_t)data_mesh.size(); } 00141 ROS_DEPRECATED void set_data_mesh_size(uint32_t size) { data_mesh.resize((size_t)size); } 00142 ROS_DEPRECATED void get_data_mesh_vec(std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other > & vec) const { vec = this->data_mesh; } 00143 ROS_DEPRECATED void set_data_mesh_vec(const std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other > & vec) { this->data_mesh = vec; } 00144 ROS_DEPRECATED uint32_t get_urdf_size() const { return (uint32_t)urdf.size(); } 00145 ROS_DEPRECATED void set_urdf_size(uint32_t size) { urdf.resize((size_t)size); } 00146 ROS_DEPRECATED void get_urdf_vec(std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other > & vec) const { vec = this->urdf; } 00147 ROS_DEPRECATED void set_urdf_vec(const std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other > & vec) { this->urdf = vec; } 00148 private: 00149 static const char* __s_getDataType_() { return "srs_object_database_msgs/InsertObjectRequest"; } 00150 public: 00151 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00152 00153 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00154 00155 private: 00156 static const char* __s_getMD5Sum_() { return "4045f8a3a36be31cf6b0274a21ca2bb4"; } 00157 public: 00158 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00159 00160 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00161 00162 private: 00163 static const char* __s_getServerMD5Sum_() { return "665c5bed07e3c52611345e1782e947e1"; } 00164 public: 00165 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00166 00167 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00168 00169 private: 00170 static const char* __s_getMessageDefinition_() { return "\n\ 00171 \n\ 00172 \n\ 00173 \n\ 00174 string function\n\ 00175 \n\ 00176 \n\ 00177 int32 model_id\n\ 00178 \n\ 00179 \n\ 00180 string model_name\n\ 00181 \n\ 00182 \n\ 00183 string model_desc\n\ 00184 \n\ 00185 \n\ 00186 string model_category\n\ 00187 \n\ 00188 \n\ 00189 float32 model_x_size\n\ 00190 \n\ 00191 \n\ 00192 float32 model_y_size\n\ 00193 \n\ 00194 \n\ 00195 float32 model_z_size\n\ 00196 \n\ 00197 \n\ 00198 string model_basic_shape\n\ 00199 \n\ 00200 \n\ 00201 bool graspable\n\ 00202 \n\ 00203 \n\ 00204 \n\ 00205 uint8[] pcl\n\ 00206 uint8[] fpt\n\ 00207 sensor_msgs/Image img\n\ 00208 string image_type\n\ 00209 uint8[] data_grasp\n\ 00210 \n\ 00211 uint8[] data_mesh\n\ 00212 string meshType\n\ 00213 uint8[] urdf\n\ 00214 \n\ 00215 \n\ 00216 ================================================================================\n\ 00217 MSG: sensor_msgs/Image\n\ 00218 # This message contains an uncompressed image\n\ 00219 # (0, 0) is at top-left corner of image\n\ 00220 #\n\ 00221 \n\ 00222 Header header # Header timestamp should be acquisition time of image\n\ 00223 # Header frame_id should be optical frame of camera\n\ 00224 # origin of frame should be optical center of cameara\n\ 00225 # +x should point to the right in the image\n\ 00226 # +y should point down in the image\n\ 00227 # +z should point into to plane of the image\n\ 00228 # If the frame_id here and the frame_id of the CameraInfo\n\ 00229 # message associated with the image conflict\n\ 00230 # the behavior is undefined\n\ 00231 \n\ 00232 uint32 height # image height, that is, number of rows\n\ 00233 uint32 width # image width, that is, number of columns\n\ 00234 \n\ 00235 # The legal values for encoding are in file src/image_encodings.cpp\n\ 00236 # If you want to standardize a new string format, join\n\ 00237 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.\n\ 00238 \n\ 00239 string encoding # Encoding of pixels -- channel meaning, ordering, size\n\ 00240 # taken from the list of strings in src/image_encodings.cpp\n\ 00241 \n\ 00242 uint8 is_bigendian # is this data bigendian?\n\ 00243 uint32 step # Full row length in bytes\n\ 00244 uint8[] data # actual matrix data, size is (step * rows)\n\ 00245 \n\ 00246 ================================================================================\n\ 00247 MSG: std_msgs/Header\n\ 00248 # Standard metadata for higher-level stamped data types.\n\ 00249 # This is generally used to communicate timestamped data \n\ 00250 # in a particular coordinate frame.\n\ 00251 # \n\ 00252 # sequence ID: consecutively increasing ID \n\ 00253 uint32 seq\n\ 00254 #Two-integer timestamp that is expressed as:\n\ 00255 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00256 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00257 # time-handling sugar is provided by the client library\n\ 00258 time stamp\n\ 00259 #Frame this data is associated with\n\ 00260 # 0: no frame\n\ 00261 # 1: global frame\n\ 00262 string frame_id\n\ 00263 \n\ 00264 "; } 00265 public: 00266 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00267 00268 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00269 00270 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00271 { 00272 ros::serialization::OStream stream(write_ptr, 1000000000); 00273 ros::serialization::serialize(stream, function); 00274 ros::serialization::serialize(stream, model_id); 00275 ros::serialization::serialize(stream, model_name); 00276 ros::serialization::serialize(stream, model_desc); 00277 ros::serialization::serialize(stream, model_category); 00278 ros::serialization::serialize(stream, model_x_size); 00279 ros::serialization::serialize(stream, model_y_size); 00280 ros::serialization::serialize(stream, model_z_size); 00281 ros::serialization::serialize(stream, model_basic_shape); 00282 ros::serialization::serialize(stream, graspable); 00283 ros::serialization::serialize(stream, pcl); 00284 ros::serialization::serialize(stream, fpt); 00285 ros::serialization::serialize(stream, img); 00286 ros::serialization::serialize(stream, image_type); 00287 ros::serialization::serialize(stream, data_grasp); 00288 ros::serialization::serialize(stream, data_mesh); 00289 ros::serialization::serialize(stream, meshType); 00290 ros::serialization::serialize(stream, urdf); 00291 return stream.getData(); 00292 } 00293 00294 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00295 { 00296 ros::serialization::IStream stream(read_ptr, 1000000000); 00297 ros::serialization::deserialize(stream, function); 00298 ros::serialization::deserialize(stream, model_id); 00299 ros::serialization::deserialize(stream, model_name); 00300 ros::serialization::deserialize(stream, model_desc); 00301 ros::serialization::deserialize(stream, model_category); 00302 ros::serialization::deserialize(stream, model_x_size); 00303 ros::serialization::deserialize(stream, model_y_size); 00304 ros::serialization::deserialize(stream, model_z_size); 00305 ros::serialization::deserialize(stream, model_basic_shape); 00306 ros::serialization::deserialize(stream, graspable); 00307 ros::serialization::deserialize(stream, pcl); 00308 ros::serialization::deserialize(stream, fpt); 00309 ros::serialization::deserialize(stream, img); 00310 ros::serialization::deserialize(stream, image_type); 00311 ros::serialization::deserialize(stream, data_grasp); 00312 ros::serialization::deserialize(stream, data_mesh); 00313 ros::serialization::deserialize(stream, meshType); 00314 ros::serialization::deserialize(stream, urdf); 00315 return stream.getData(); 00316 } 00317 00318 ROS_DEPRECATED virtual uint32_t serializationLength() const 00319 { 00320 uint32_t size = 0; 00321 size += ros::serialization::serializationLength(function); 00322 size += ros::serialization::serializationLength(model_id); 00323 size += ros::serialization::serializationLength(model_name); 00324 size += ros::serialization::serializationLength(model_desc); 00325 size += ros::serialization::serializationLength(model_category); 00326 size += ros::serialization::serializationLength(model_x_size); 00327 size += ros::serialization::serializationLength(model_y_size); 00328 size += ros::serialization::serializationLength(model_z_size); 00329 size += ros::serialization::serializationLength(model_basic_shape); 00330 size += ros::serialization::serializationLength(graspable); 00331 size += ros::serialization::serializationLength(pcl); 00332 size += ros::serialization::serializationLength(fpt); 00333 size += ros::serialization::serializationLength(img); 00334 size += ros::serialization::serializationLength(image_type); 00335 size += ros::serialization::serializationLength(data_grasp); 00336 size += ros::serialization::serializationLength(data_mesh); 00337 size += ros::serialization::serializationLength(meshType); 00338 size += ros::serialization::serializationLength(urdf); 00339 return size; 00340 } 00341 00342 typedef boost::shared_ptr< ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> > Ptr; 00343 typedef boost::shared_ptr< ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> const> ConstPtr; 00344 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00345 }; // struct InsertObjectRequest 00346 typedef ::srs_object_database_msgs::InsertObjectRequest_<std::allocator<void> > InsertObjectRequest; 00347 00348 typedef boost::shared_ptr< ::srs_object_database_msgs::InsertObjectRequest> InsertObjectRequestPtr; 00349 typedef boost::shared_ptr< ::srs_object_database_msgs::InsertObjectRequest const> InsertObjectRequestConstPtr; 00350 00351 00352 template <class ContainerAllocator> 00353 struct InsertObjectResponse_ { 00354 typedef InsertObjectResponse_<ContainerAllocator> Type; 00355 00356 InsertObjectResponse_() 00357 : return_response() 00358 , model_id(0) 00359 { 00360 } 00361 00362 InsertObjectResponse_(const ContainerAllocator& _alloc) 00363 : return_response(_alloc) 00364 , model_id(0) 00365 { 00366 } 00367 00368 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _return_response_type; 00369 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > return_response; 00370 00371 typedef int32_t _model_id_type; 00372 int32_t model_id; 00373 00374 00375 private: 00376 static const char* __s_getDataType_() { return "srs_object_database_msgs/InsertObjectResponse"; } 00377 public: 00378 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00379 00380 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00381 00382 private: 00383 static const char* __s_getMD5Sum_() { return "bcd4a8cb19bdcae33e0a74fc2d3b2e46"; } 00384 public: 00385 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00386 00387 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00388 00389 private: 00390 static const char* __s_getServerMD5Sum_() { return "665c5bed07e3c52611345e1782e947e1"; } 00391 public: 00392 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00393 00394 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00395 00396 private: 00397 static const char* __s_getMessageDefinition_() { return "\n\ 00398 \n\ 00399 string return_response\n\ 00400 \n\ 00401 int32 model_id\n\ 00402 \n\ 00403 \n\ 00404 \n\ 00405 "; } 00406 public: 00407 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00408 00409 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00410 00411 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00412 { 00413 ros::serialization::OStream stream(write_ptr, 1000000000); 00414 ros::serialization::serialize(stream, return_response); 00415 ros::serialization::serialize(stream, model_id); 00416 return stream.getData(); 00417 } 00418 00419 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00420 { 00421 ros::serialization::IStream stream(read_ptr, 1000000000); 00422 ros::serialization::deserialize(stream, return_response); 00423 ros::serialization::deserialize(stream, model_id); 00424 return stream.getData(); 00425 } 00426 00427 ROS_DEPRECATED virtual uint32_t serializationLength() const 00428 { 00429 uint32_t size = 0; 00430 size += ros::serialization::serializationLength(return_response); 00431 size += ros::serialization::serializationLength(model_id); 00432 return size; 00433 } 00434 00435 typedef boost::shared_ptr< ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> > Ptr; 00436 typedef boost::shared_ptr< ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> const> ConstPtr; 00437 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00438 }; // struct InsertObjectResponse 00439 typedef ::srs_object_database_msgs::InsertObjectResponse_<std::allocator<void> > InsertObjectResponse; 00440 00441 typedef boost::shared_ptr< ::srs_object_database_msgs::InsertObjectResponse> InsertObjectResponsePtr; 00442 typedef boost::shared_ptr< ::srs_object_database_msgs::InsertObjectResponse const> InsertObjectResponseConstPtr; 00443 00444 struct InsertObject 00445 { 00446 00447 typedef InsertObjectRequest Request; 00448 typedef InsertObjectResponse Response; 00449 Request request; 00450 Response response; 00451 00452 typedef Request RequestType; 00453 typedef Response ResponseType; 00454 }; // struct InsertObject 00455 } // namespace srs_object_database_msgs 00456 00457 namespace ros 00458 { 00459 namespace message_traits 00460 { 00461 template<class ContainerAllocator> struct IsMessage< ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> > : public TrueType {}; 00462 template<class ContainerAllocator> struct IsMessage< ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> const> : public TrueType {}; 00463 template<class ContainerAllocator> 00464 struct MD5Sum< ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> > { 00465 static const char* value() 00466 { 00467 return "4045f8a3a36be31cf6b0274a21ca2bb4"; 00468 } 00469 00470 static const char* value(const ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> &) { return value(); } 00471 static const uint64_t static_value1 = 0x4045f8a3a36be31cULL; 00472 static const uint64_t static_value2 = 0xf6b0274a21ca2bb4ULL; 00473 }; 00474 00475 template<class ContainerAllocator> 00476 struct DataType< ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> > { 00477 static const char* value() 00478 { 00479 return "srs_object_database_msgs/InsertObjectRequest"; 00480 } 00481 00482 static const char* value(const ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> &) { return value(); } 00483 }; 00484 00485 template<class ContainerAllocator> 00486 struct Definition< ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> > { 00487 static const char* value() 00488 { 00489 return "\n\ 00490 \n\ 00491 \n\ 00492 \n\ 00493 string function\n\ 00494 \n\ 00495 \n\ 00496 int32 model_id\n\ 00497 \n\ 00498 \n\ 00499 string model_name\n\ 00500 \n\ 00501 \n\ 00502 string model_desc\n\ 00503 \n\ 00504 \n\ 00505 string model_category\n\ 00506 \n\ 00507 \n\ 00508 float32 model_x_size\n\ 00509 \n\ 00510 \n\ 00511 float32 model_y_size\n\ 00512 \n\ 00513 \n\ 00514 float32 model_z_size\n\ 00515 \n\ 00516 \n\ 00517 string model_basic_shape\n\ 00518 \n\ 00519 \n\ 00520 bool graspable\n\ 00521 \n\ 00522 \n\ 00523 \n\ 00524 uint8[] pcl\n\ 00525 uint8[] fpt\n\ 00526 sensor_msgs/Image img\n\ 00527 string image_type\n\ 00528 uint8[] data_grasp\n\ 00529 \n\ 00530 uint8[] data_mesh\n\ 00531 string meshType\n\ 00532 uint8[] urdf\n\ 00533 \n\ 00534 \n\ 00535 ================================================================================\n\ 00536 MSG: sensor_msgs/Image\n\ 00537 # This message contains an uncompressed image\n\ 00538 # (0, 0) is at top-left corner of image\n\ 00539 #\n\ 00540 \n\ 00541 Header header # Header timestamp should be acquisition time of image\n\ 00542 # Header frame_id should be optical frame of camera\n\ 00543 # origin of frame should be optical center of cameara\n\ 00544 # +x should point to the right in the image\n\ 00545 # +y should point down in the image\n\ 00546 # +z should point into to plane of the image\n\ 00547 # If the frame_id here and the frame_id of the CameraInfo\n\ 00548 # message associated with the image conflict\n\ 00549 # the behavior is undefined\n\ 00550 \n\ 00551 uint32 height # image height, that is, number of rows\n\ 00552 uint32 width # image width, that is, number of columns\n\ 00553 \n\ 00554 # The legal values for encoding are in file src/image_encodings.cpp\n\ 00555 # If you want to standardize a new string format, join\n\ 00556 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.\n\ 00557 \n\ 00558 string encoding # Encoding of pixels -- channel meaning, ordering, size\n\ 00559 # taken from the list of strings in src/image_encodings.cpp\n\ 00560 \n\ 00561 uint8 is_bigendian # is this data bigendian?\n\ 00562 uint32 step # Full row length in bytes\n\ 00563 uint8[] data # actual matrix data, size is (step * rows)\n\ 00564 \n\ 00565 ================================================================================\n\ 00566 MSG: std_msgs/Header\n\ 00567 # Standard metadata for higher-level stamped data types.\n\ 00568 # This is generally used to communicate timestamped data \n\ 00569 # in a particular coordinate frame.\n\ 00570 # \n\ 00571 # sequence ID: consecutively increasing ID \n\ 00572 uint32 seq\n\ 00573 #Two-integer timestamp that is expressed as:\n\ 00574 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00575 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00576 # time-handling sugar is provided by the client library\n\ 00577 time stamp\n\ 00578 #Frame this data is associated with\n\ 00579 # 0: no frame\n\ 00580 # 1: global frame\n\ 00581 string frame_id\n\ 00582 \n\ 00583 "; 00584 } 00585 00586 static const char* value(const ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> &) { return value(); } 00587 }; 00588 00589 } // namespace message_traits 00590 } // namespace ros 00591 00592 00593 namespace ros 00594 { 00595 namespace message_traits 00596 { 00597 template<class ContainerAllocator> struct IsMessage< ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> > : public TrueType {}; 00598 template<class ContainerAllocator> struct IsMessage< ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> const> : public TrueType {}; 00599 template<class ContainerAllocator> 00600 struct MD5Sum< ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> > { 00601 static const char* value() 00602 { 00603 return "bcd4a8cb19bdcae33e0a74fc2d3b2e46"; 00604 } 00605 00606 static const char* value(const ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> &) { return value(); } 00607 static const uint64_t static_value1 = 0xbcd4a8cb19bdcae3ULL; 00608 static const uint64_t static_value2 = 0x3e0a74fc2d3b2e46ULL; 00609 }; 00610 00611 template<class ContainerAllocator> 00612 struct DataType< ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> > { 00613 static const char* value() 00614 { 00615 return "srs_object_database_msgs/InsertObjectResponse"; 00616 } 00617 00618 static const char* value(const ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> &) { return value(); } 00619 }; 00620 00621 template<class ContainerAllocator> 00622 struct Definition< ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> > { 00623 static const char* value() 00624 { 00625 return "\n\ 00626 \n\ 00627 string return_response\n\ 00628 \n\ 00629 int32 model_id\n\ 00630 \n\ 00631 \n\ 00632 \n\ 00633 "; 00634 } 00635 00636 static const char* value(const ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> &) { return value(); } 00637 }; 00638 00639 } // namespace message_traits 00640 } // namespace ros 00641 00642 namespace ros 00643 { 00644 namespace serialization 00645 { 00646 00647 template<class ContainerAllocator> struct Serializer< ::srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> > 00648 { 00649 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00650 { 00651 stream.next(m.function); 00652 stream.next(m.model_id); 00653 stream.next(m.model_name); 00654 stream.next(m.model_desc); 00655 stream.next(m.model_category); 00656 stream.next(m.model_x_size); 00657 stream.next(m.model_y_size); 00658 stream.next(m.model_z_size); 00659 stream.next(m.model_basic_shape); 00660 stream.next(m.graspable); 00661 stream.next(m.pcl); 00662 stream.next(m.fpt); 00663 stream.next(m.img); 00664 stream.next(m.image_type); 00665 stream.next(m.data_grasp); 00666 stream.next(m.data_mesh); 00667 stream.next(m.meshType); 00668 stream.next(m.urdf); 00669 } 00670 00671 ROS_DECLARE_ALLINONE_SERIALIZER; 00672 }; // struct InsertObjectRequest_ 00673 } // namespace serialization 00674 } // namespace ros 00675 00676 00677 namespace ros 00678 { 00679 namespace serialization 00680 { 00681 00682 template<class ContainerAllocator> struct Serializer< ::srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> > 00683 { 00684 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00685 { 00686 stream.next(m.return_response); 00687 stream.next(m.model_id); 00688 } 00689 00690 ROS_DECLARE_ALLINONE_SERIALIZER; 00691 }; // struct InsertObjectResponse_ 00692 } // namespace serialization 00693 } // namespace ros 00694 00695 namespace ros 00696 { 00697 namespace service_traits 00698 { 00699 template<> 00700 struct MD5Sum<srs_object_database_msgs::InsertObject> { 00701 static const char* value() 00702 { 00703 return "665c5bed07e3c52611345e1782e947e1"; 00704 } 00705 00706 static const char* value(const srs_object_database_msgs::InsertObject&) { return value(); } 00707 }; 00708 00709 template<> 00710 struct DataType<srs_object_database_msgs::InsertObject> { 00711 static const char* value() 00712 { 00713 return "srs_object_database_msgs/InsertObject"; 00714 } 00715 00716 static const char* value(const srs_object_database_msgs::InsertObject&) { return value(); } 00717 }; 00718 00719 template<class ContainerAllocator> 00720 struct MD5Sum<srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> > { 00721 static const char* value() 00722 { 00723 return "665c5bed07e3c52611345e1782e947e1"; 00724 } 00725 00726 static const char* value(const srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> &) { return value(); } 00727 }; 00728 00729 template<class ContainerAllocator> 00730 struct DataType<srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> > { 00731 static const char* value() 00732 { 00733 return "srs_object_database_msgs/InsertObject"; 00734 } 00735 00736 static const char* value(const srs_object_database_msgs::InsertObjectRequest_<ContainerAllocator> &) { return value(); } 00737 }; 00738 00739 template<class ContainerAllocator> 00740 struct MD5Sum<srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> > { 00741 static const char* value() 00742 { 00743 return "665c5bed07e3c52611345e1782e947e1"; 00744 } 00745 00746 static const char* value(const srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> &) { return value(); } 00747 }; 00748 00749 template<class ContainerAllocator> 00750 struct DataType<srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> > { 00751 static const char* value() 00752 { 00753 return "srs_object_database_msgs/InsertObject"; 00754 } 00755 00756 static const char* value(const srs_object_database_msgs::InsertObjectResponse_<ContainerAllocator> &) { return value(); } 00757 }; 00758 00759 } // namespace service_traits 00760 } // namespace ros 00761 00762 #endif // SRS_OBJECT_DATABASE_MSGS_SERVICE_INSERTOBJECT_H 00763