00001
00002 #ifndef GRASPIT_INTERFACE_MSGS_SERVICE_LOADDATABASEMODEL_H
00003 #define GRASPIT_INTERFACE_MSGS_SERVICE_LOADDATABASEMODEL_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 "geometry_msgs/Pose.h"
00020
00021
00022
00023 namespace graspit_interface_msgs
00024 {
00025 template <class ContainerAllocator>
00026 struct LoadDatabaseModelRequest_ {
00027 typedef LoadDatabaseModelRequest_<ContainerAllocator> Type;
00028
00029 LoadDatabaseModelRequest_()
00030 : model_id(0)
00031 , model_pose()
00032 , clear_other_models(false)
00033 {
00034 }
00035
00036 LoadDatabaseModelRequest_(const ContainerAllocator& _alloc)
00037 : model_id(0)
00038 , model_pose(_alloc)
00039 , clear_other_models(false)
00040 {
00041 }
00042
00043 typedef int32_t _model_id_type;
00044 int32_t model_id;
00045
00046 typedef ::geometry_msgs::Pose_<ContainerAllocator> _model_pose_type;
00047 ::geometry_msgs::Pose_<ContainerAllocator> model_pose;
00048
00049 typedef uint8_t _clear_other_models_type;
00050 uint8_t clear_other_models;
00051
00052
00053 private:
00054 static const char* __s_getDataType_() { return "graspit_interface_msgs/LoadDatabaseModelRequest"; }
00055 public:
00056 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00057
00058 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00059
00060 private:
00061 static const char* __s_getMD5Sum_() { return "e0142126fa25500956c0574c8caa1798"; }
00062 public:
00063 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00064
00065 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00066
00067 private:
00068 static const char* __s_getServerMD5Sum_() { return "8e7f810fdd6e19434987115ec75645ca"; }
00069 public:
00070 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00071
00072 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00073
00074 private:
00075 static const char* __s_getMessageDefinition_() { return "\n\
00076 \n\
00077 \n\
00078 \n\
00079 \n\
00080 int32 model_id\n\
00081 \n\
00082 \n\
00083 geometry_msgs/Pose model_pose\n\
00084 \n\
00085 \n\
00086 \n\
00087 bool clear_other_models\n\
00088 \n\
00089 \n\
00090 ================================================================================\n\
00091 MSG: geometry_msgs/Pose\n\
00092 # A representation of pose in free space, composed of postion and orientation. \n\
00093 Point position\n\
00094 Quaternion orientation\n\
00095 \n\
00096 ================================================================================\n\
00097 MSG: geometry_msgs/Point\n\
00098 # This contains the position of a point in free space\n\
00099 float64 x\n\
00100 float64 y\n\
00101 float64 z\n\
00102 \n\
00103 ================================================================================\n\
00104 MSG: geometry_msgs/Quaternion\n\
00105 # This represents an orientation in free space in quaternion form.\n\
00106 \n\
00107 float64 x\n\
00108 float64 y\n\
00109 float64 z\n\
00110 float64 w\n\
00111 \n\
00112 "; }
00113 public:
00114 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00115
00116 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00117
00118 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00119 {
00120 ros::serialization::OStream stream(write_ptr, 1000000000);
00121 ros::serialization::serialize(stream, model_id);
00122 ros::serialization::serialize(stream, model_pose);
00123 ros::serialization::serialize(stream, clear_other_models);
00124 return stream.getData();
00125 }
00126
00127 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00128 {
00129 ros::serialization::IStream stream(read_ptr, 1000000000);
00130 ros::serialization::deserialize(stream, model_id);
00131 ros::serialization::deserialize(stream, model_pose);
00132 ros::serialization::deserialize(stream, clear_other_models);
00133 return stream.getData();
00134 }
00135
00136 ROS_DEPRECATED virtual uint32_t serializationLength() const
00137 {
00138 uint32_t size = 0;
00139 size += ros::serialization::serializationLength(model_id);
00140 size += ros::serialization::serializationLength(model_pose);
00141 size += ros::serialization::serializationLength(clear_other_models);
00142 return size;
00143 }
00144
00145 typedef boost::shared_ptr< ::graspit_interface_msgs::LoadDatabaseModelRequest_<ContainerAllocator> > Ptr;
00146 typedef boost::shared_ptr< ::graspit_interface_msgs::LoadDatabaseModelRequest_<ContainerAllocator> const> ConstPtr;
00147 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00148 };
00149 typedef ::graspit_interface_msgs::LoadDatabaseModelRequest_<std::allocator<void> > LoadDatabaseModelRequest;
00150
00151 typedef boost::shared_ptr< ::graspit_interface_msgs::LoadDatabaseModelRequest> LoadDatabaseModelRequestPtr;
00152 typedef boost::shared_ptr< ::graspit_interface_msgs::LoadDatabaseModelRequest const> LoadDatabaseModelRequestConstPtr;
00153
00154
00155 template <class ContainerAllocator>
00156 struct LoadDatabaseModelResponse_ {
00157 typedef LoadDatabaseModelResponse_<ContainerAllocator> Type;
00158
00159 LoadDatabaseModelResponse_()
00160 : result(0)
00161 {
00162 }
00163
00164 LoadDatabaseModelResponse_(const ContainerAllocator& _alloc)
00165 : result(0)
00166 {
00167 }
00168
00169 typedef int32_t _result_type;
00170 int32_t result;
00171
00172 enum { LOAD_SUCCESS = 0 };
00173 enum { LOAD_FAILURE = 1 };
00174
00175 private:
00176 static const char* __s_getDataType_() { return "graspit_interface_msgs/LoadDatabaseModelResponse"; }
00177 public:
00178 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00179
00180 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00181
00182 private:
00183 static const char* __s_getMD5Sum_() { return "41e017e2964af6197c0f07ec9353afaf"; }
00184 public:
00185 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00186
00187 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00188
00189 private:
00190 static const char* __s_getServerMD5Sum_() { return "8e7f810fdd6e19434987115ec75645ca"; }
00191 public:
00192 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00193
00194 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00195
00196 private:
00197 static const char* __s_getMessageDefinition_() { return "\n\
00198 int32 LOAD_SUCCESS = 0\n\
00199 int32 LOAD_FAILURE = 1\n\
00200 int32 result\n\
00201 \n\
00202 "; }
00203 public:
00204 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00205
00206 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00207
00208 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00209 {
00210 ros::serialization::OStream stream(write_ptr, 1000000000);
00211 ros::serialization::serialize(stream, result);
00212 return stream.getData();
00213 }
00214
00215 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00216 {
00217 ros::serialization::IStream stream(read_ptr, 1000000000);
00218 ros::serialization::deserialize(stream, result);
00219 return stream.getData();
00220 }
00221
00222 ROS_DEPRECATED virtual uint32_t serializationLength() const
00223 {
00224 uint32_t size = 0;
00225 size += ros::serialization::serializationLength(result);
00226 return size;
00227 }
00228
00229 typedef boost::shared_ptr< ::graspit_interface_msgs::LoadDatabaseModelResponse_<ContainerAllocator> > Ptr;
00230 typedef boost::shared_ptr< ::graspit_interface_msgs::LoadDatabaseModelResponse_<ContainerAllocator> const> ConstPtr;
00231 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00232 };
00233 typedef ::graspit_interface_msgs::LoadDatabaseModelResponse_<std::allocator<void> > LoadDatabaseModelResponse;
00234
00235 typedef boost::shared_ptr< ::graspit_interface_msgs::LoadDatabaseModelResponse> LoadDatabaseModelResponsePtr;
00236 typedef boost::shared_ptr< ::graspit_interface_msgs::LoadDatabaseModelResponse const> LoadDatabaseModelResponseConstPtr;
00237
00238 struct LoadDatabaseModel
00239 {
00240
00241 typedef LoadDatabaseModelRequest Request;
00242 typedef LoadDatabaseModelResponse Response;
00243 Request request;
00244 Response response;
00245
00246 typedef Request RequestType;
00247 typedef Response ResponseType;
00248 };
00249 }
00250
00251 namespace ros
00252 {
00253 namespace message_traits
00254 {
00255 template<class ContainerAllocator> struct IsMessage< ::graspit_interface_msgs::LoadDatabaseModelRequest_<ContainerAllocator> > : public TrueType {};
00256 template<class ContainerAllocator> struct IsMessage< ::graspit_interface_msgs::LoadDatabaseModelRequest_<ContainerAllocator> const> : public TrueType {};
00257 template<class ContainerAllocator>
00258 struct MD5Sum< ::graspit_interface_msgs::LoadDatabaseModelRequest_<ContainerAllocator> > {
00259 static const char* value()
00260 {
00261 return "e0142126fa25500956c0574c8caa1798";
00262 }
00263
00264 static const char* value(const ::graspit_interface_msgs::LoadDatabaseModelRequest_<ContainerAllocator> &) { return value(); }
00265 static const uint64_t static_value1 = 0xe0142126fa255009ULL;
00266 static const uint64_t static_value2 = 0x56c0574c8caa1798ULL;
00267 };
00268
00269 template<class ContainerAllocator>
00270 struct DataType< ::graspit_interface_msgs::LoadDatabaseModelRequest_<ContainerAllocator> > {
00271 static const char* value()
00272 {
00273 return "graspit_interface_msgs/LoadDatabaseModelRequest";
00274 }
00275
00276 static const char* value(const ::graspit_interface_msgs::LoadDatabaseModelRequest_<ContainerAllocator> &) { return value(); }
00277 };
00278
00279 template<class ContainerAllocator>
00280 struct Definition< ::graspit_interface_msgs::LoadDatabaseModelRequest_<ContainerAllocator> > {
00281 static const char* value()
00282 {
00283 return "\n\
00284 \n\
00285 \n\
00286 \n\
00287 \n\
00288 int32 model_id\n\
00289 \n\
00290 \n\
00291 geometry_msgs/Pose model_pose\n\
00292 \n\
00293 \n\
00294 \n\
00295 bool clear_other_models\n\
00296 \n\
00297 \n\
00298 ================================================================================\n\
00299 MSG: geometry_msgs/Pose\n\
00300 # A representation of pose in free space, composed of postion and orientation. \n\
00301 Point position\n\
00302 Quaternion orientation\n\
00303 \n\
00304 ================================================================================\n\
00305 MSG: geometry_msgs/Point\n\
00306 # This contains the position of a point in free space\n\
00307 float64 x\n\
00308 float64 y\n\
00309 float64 z\n\
00310 \n\
00311 ================================================================================\n\
00312 MSG: geometry_msgs/Quaternion\n\
00313 # This represents an orientation in free space in quaternion form.\n\
00314 \n\
00315 float64 x\n\
00316 float64 y\n\
00317 float64 z\n\
00318 float64 w\n\
00319 \n\
00320 ";
00321 }
00322
00323 static const char* value(const ::graspit_interface_msgs::LoadDatabaseModelRequest_<ContainerAllocator> &) { return value(); }
00324 };
00325
00326 template<class ContainerAllocator> struct IsFixedSize< ::graspit_interface_msgs::LoadDatabaseModelRequest_<ContainerAllocator> > : public TrueType {};
00327 }
00328 }
00329
00330
00331 namespace ros
00332 {
00333 namespace message_traits
00334 {
00335 template<class ContainerAllocator> struct IsMessage< ::graspit_interface_msgs::LoadDatabaseModelResponse_<ContainerAllocator> > : public TrueType {};
00336 template<class ContainerAllocator> struct IsMessage< ::graspit_interface_msgs::LoadDatabaseModelResponse_<ContainerAllocator> const> : public TrueType {};
00337 template<class ContainerAllocator>
00338 struct MD5Sum< ::graspit_interface_msgs::LoadDatabaseModelResponse_<ContainerAllocator> > {
00339 static const char* value()
00340 {
00341 return "41e017e2964af6197c0f07ec9353afaf";
00342 }
00343
00344 static const char* value(const ::graspit_interface_msgs::LoadDatabaseModelResponse_<ContainerAllocator> &) { return value(); }
00345 static const uint64_t static_value1 = 0x41e017e2964af619ULL;
00346 static const uint64_t static_value2 = 0x7c0f07ec9353afafULL;
00347 };
00348
00349 template<class ContainerAllocator>
00350 struct DataType< ::graspit_interface_msgs::LoadDatabaseModelResponse_<ContainerAllocator> > {
00351 static const char* value()
00352 {
00353 return "graspit_interface_msgs/LoadDatabaseModelResponse";
00354 }
00355
00356 static const char* value(const ::graspit_interface_msgs::LoadDatabaseModelResponse_<ContainerAllocator> &) { return value(); }
00357 };
00358
00359 template<class ContainerAllocator>
00360 struct Definition< ::graspit_interface_msgs::LoadDatabaseModelResponse_<ContainerAllocator> > {
00361 static const char* value()
00362 {
00363 return "\n\
00364 int32 LOAD_SUCCESS = 0\n\
00365 int32 LOAD_FAILURE = 1\n\
00366 int32 result\n\
00367 \n\
00368 ";
00369 }
00370
00371 static const char* value(const ::graspit_interface_msgs::LoadDatabaseModelResponse_<ContainerAllocator> &) { return value(); }
00372 };
00373
00374 template<class ContainerAllocator> struct IsFixedSize< ::graspit_interface_msgs::LoadDatabaseModelResponse_<ContainerAllocator> > : public TrueType {};
00375 }
00376 }
00377
00378 namespace ros
00379 {
00380 namespace serialization
00381 {
00382
00383 template<class ContainerAllocator> struct Serializer< ::graspit_interface_msgs::LoadDatabaseModelRequest_<ContainerAllocator> >
00384 {
00385 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00386 {
00387 stream.next(m.model_id);
00388 stream.next(m.model_pose);
00389 stream.next(m.clear_other_models);
00390 }
00391
00392 ROS_DECLARE_ALLINONE_SERIALIZER;
00393 };
00394 }
00395 }
00396
00397
00398 namespace ros
00399 {
00400 namespace serialization
00401 {
00402
00403 template<class ContainerAllocator> struct Serializer< ::graspit_interface_msgs::LoadDatabaseModelResponse_<ContainerAllocator> >
00404 {
00405 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00406 {
00407 stream.next(m.result);
00408 }
00409
00410 ROS_DECLARE_ALLINONE_SERIALIZER;
00411 };
00412 }
00413 }
00414
00415 namespace ros
00416 {
00417 namespace service_traits
00418 {
00419 template<>
00420 struct MD5Sum<graspit_interface_msgs::LoadDatabaseModel> {
00421 static const char* value()
00422 {
00423 return "8e7f810fdd6e19434987115ec75645ca";
00424 }
00425
00426 static const char* value(const graspit_interface_msgs::LoadDatabaseModel&) { return value(); }
00427 };
00428
00429 template<>
00430 struct DataType<graspit_interface_msgs::LoadDatabaseModel> {
00431 static const char* value()
00432 {
00433 return "graspit_interface_msgs/LoadDatabaseModel";
00434 }
00435
00436 static const char* value(const graspit_interface_msgs::LoadDatabaseModel&) { return value(); }
00437 };
00438
00439 template<class ContainerAllocator>
00440 struct MD5Sum<graspit_interface_msgs::LoadDatabaseModelRequest_<ContainerAllocator> > {
00441 static const char* value()
00442 {
00443 return "8e7f810fdd6e19434987115ec75645ca";
00444 }
00445
00446 static const char* value(const graspit_interface_msgs::LoadDatabaseModelRequest_<ContainerAllocator> &) { return value(); }
00447 };
00448
00449 template<class ContainerAllocator>
00450 struct DataType<graspit_interface_msgs::LoadDatabaseModelRequest_<ContainerAllocator> > {
00451 static const char* value()
00452 {
00453 return "graspit_interface_msgs/LoadDatabaseModel";
00454 }
00455
00456 static const char* value(const graspit_interface_msgs::LoadDatabaseModelRequest_<ContainerAllocator> &) { return value(); }
00457 };
00458
00459 template<class ContainerAllocator>
00460 struct MD5Sum<graspit_interface_msgs::LoadDatabaseModelResponse_<ContainerAllocator> > {
00461 static const char* value()
00462 {
00463 return "8e7f810fdd6e19434987115ec75645ca";
00464 }
00465
00466 static const char* value(const graspit_interface_msgs::LoadDatabaseModelResponse_<ContainerAllocator> &) { return value(); }
00467 };
00468
00469 template<class ContainerAllocator>
00470 struct DataType<graspit_interface_msgs::LoadDatabaseModelResponse_<ContainerAllocator> > {
00471 static const char* value()
00472 {
00473 return "graspit_interface_msgs/LoadDatabaseModel";
00474 }
00475
00476 static const char* value(const graspit_interface_msgs::LoadDatabaseModelResponse_<ContainerAllocator> &) { return value(); }
00477 };
00478
00479 }
00480 }
00481
00482 #endif // GRASPIT_INTERFACE_MSGS_SERVICE_LOADDATABASEMODEL_H
00483