$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-srs_public/doc_stacks/2013-03-05_12-22-34.333426/srs_public/srs_symbolic_grounding/srv/SymbolGroundingGraspBasePoseExperimental.srv */ 00002 #ifndef SRS_SYMBOLIC_GROUNDING_SERVICE_SYMBOLGROUNDINGGRASPBASEPOSEEXPERIMENTAL_H 00003 #define SRS_SYMBOLIC_GROUNDING_SERVICE_SYMBOLGROUNDINGGRASPBASEPOSEEXPERIMENTAL_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 #include "srs_msgs/SRSSpatialInfo.h" 00021 #include "srs_msgs/SRSSpatialInfo.h" 00022 00023 00024 #include "geometry_msgs/Pose2D.h" 00025 00026 namespace srs_symbolic_grounding 00027 { 00028 template <class ContainerAllocator> 00029 struct SymbolGroundingGraspBasePoseExperimentalRequest_ { 00030 typedef SymbolGroundingGraspBasePoseExperimentalRequest_<ContainerAllocator> Type; 00031 00032 SymbolGroundingGraspBasePoseExperimentalRequest_() 00033 : target_obj_pose() 00034 , parent_obj_geometry() 00035 , furniture_geometry_list() 00036 { 00037 } 00038 00039 SymbolGroundingGraspBasePoseExperimentalRequest_(const ContainerAllocator& _alloc) 00040 : target_obj_pose(_alloc) 00041 , parent_obj_geometry(_alloc) 00042 , furniture_geometry_list(_alloc) 00043 { 00044 } 00045 00046 typedef ::geometry_msgs::Pose_<ContainerAllocator> _target_obj_pose_type; 00047 ::geometry_msgs::Pose_<ContainerAllocator> target_obj_pose; 00048 00049 typedef ::srs_msgs::SRSSpatialInfo_<ContainerAllocator> _parent_obj_geometry_type; 00050 ::srs_msgs::SRSSpatialInfo_<ContainerAllocator> parent_obj_geometry; 00051 00052 typedef std::vector< ::srs_msgs::SRSSpatialInfo_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::srs_msgs::SRSSpatialInfo_<ContainerAllocator> >::other > _furniture_geometry_list_type; 00053 std::vector< ::srs_msgs::SRSSpatialInfo_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::srs_msgs::SRSSpatialInfo_<ContainerAllocator> >::other > furniture_geometry_list; 00054 00055 00056 ROS_DEPRECATED uint32_t get_furniture_geometry_list_size() const { return (uint32_t)furniture_geometry_list.size(); } 00057 ROS_DEPRECATED void set_furniture_geometry_list_size(uint32_t size) { furniture_geometry_list.resize((size_t)size); } 00058 ROS_DEPRECATED void get_furniture_geometry_list_vec(std::vector< ::srs_msgs::SRSSpatialInfo_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::srs_msgs::SRSSpatialInfo_<ContainerAllocator> >::other > & vec) const { vec = this->furniture_geometry_list; } 00059 ROS_DEPRECATED void set_furniture_geometry_list_vec(const std::vector< ::srs_msgs::SRSSpatialInfo_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::srs_msgs::SRSSpatialInfo_<ContainerAllocator> >::other > & vec) { this->furniture_geometry_list = vec; } 00060 private: 00061 static const char* __s_getDataType_() { return "srs_symbolic_grounding/SymbolGroundingGraspBasePoseExperimentalRequest"; } 00062 public: 00063 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00064 00065 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00066 00067 private: 00068 static const char* __s_getMD5Sum_() { return "929217c873801a8d83a0ef0a0ff55374"; } 00069 public: 00070 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00071 00072 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00073 00074 private: 00075 static const char* __s_getServerMD5Sum_() { return "80365e2dd1e4f246fb4542bfaa7f0518"; } 00076 public: 00077 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00078 00079 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00080 00081 private: 00082 static const char* __s_getMessageDefinition_() { return "geometry_msgs/Pose target_obj_pose\n\ 00083 \n\ 00084 \n\ 00085 srs_msgs/SRSSpatialInfo parent_obj_geometry\n\ 00086 srs_msgs/SRSSpatialInfo[] furniture_geometry_list\n\ 00087 \n\ 00088 ================================================================================\n\ 00089 MSG: geometry_msgs/Pose\n\ 00090 # A representation of pose in free space, composed of postion and orientation. \n\ 00091 Point position\n\ 00092 Quaternion orientation\n\ 00093 \n\ 00094 ================================================================================\n\ 00095 MSG: geometry_msgs/Point\n\ 00096 # This contains the position of a point in free space\n\ 00097 float64 x\n\ 00098 float64 y\n\ 00099 float64 z\n\ 00100 \n\ 00101 ================================================================================\n\ 00102 MSG: geometry_msgs/Quaternion\n\ 00103 # This represents an orientation in free space in quaternion form.\n\ 00104 \n\ 00105 float64 x\n\ 00106 float64 y\n\ 00107 float64 z\n\ 00108 float64 w\n\ 00109 \n\ 00110 ================================================================================\n\ 00111 MSG: srs_msgs/SRSSpatialInfo\n\ 00112 # Point point\n\ 00113 # Orientation angles\n\ 00114 float32 l\n\ 00115 float32 w\n\ 00116 float32 h\n\ 00117 \n\ 00118 geometry_msgs/Pose pose\n\ 00119 \n\ 00120 "; } 00121 public: 00122 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00123 00124 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00125 00126 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00127 { 00128 ros::serialization::OStream stream(write_ptr, 1000000000); 00129 ros::serialization::serialize(stream, target_obj_pose); 00130 ros::serialization::serialize(stream, parent_obj_geometry); 00131 ros::serialization::serialize(stream, furniture_geometry_list); 00132 return stream.getData(); 00133 } 00134 00135 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00136 { 00137 ros::serialization::IStream stream(read_ptr, 1000000000); 00138 ros::serialization::deserialize(stream, target_obj_pose); 00139 ros::serialization::deserialize(stream, parent_obj_geometry); 00140 ros::serialization::deserialize(stream, furniture_geometry_list); 00141 return stream.getData(); 00142 } 00143 00144 ROS_DEPRECATED virtual uint32_t serializationLength() const 00145 { 00146 uint32_t size = 0; 00147 size += ros::serialization::serializationLength(target_obj_pose); 00148 size += ros::serialization::serializationLength(parent_obj_geometry); 00149 size += ros::serialization::serializationLength(furniture_geometry_list); 00150 return size; 00151 } 00152 00153 typedef boost::shared_ptr< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalRequest_<ContainerAllocator> > Ptr; 00154 typedef boost::shared_ptr< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalRequest_<ContainerAllocator> const> ConstPtr; 00155 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00156 }; // struct SymbolGroundingGraspBasePoseExperimentalRequest 00157 typedef ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalRequest_<std::allocator<void> > SymbolGroundingGraspBasePoseExperimentalRequest; 00158 00159 typedef boost::shared_ptr< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalRequest> SymbolGroundingGraspBasePoseExperimentalRequestPtr; 00160 typedef boost::shared_ptr< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalRequest const> SymbolGroundingGraspBasePoseExperimentalRequestConstPtr; 00161 00162 00163 template <class ContainerAllocator> 00164 struct SymbolGroundingGraspBasePoseExperimentalResponse_ { 00165 typedef SymbolGroundingGraspBasePoseExperimentalResponse_<ContainerAllocator> Type; 00166 00167 SymbolGroundingGraspBasePoseExperimentalResponse_() 00168 : obstacle_check(false) 00169 , reach(0.0) 00170 , grasp_base_pose() 00171 { 00172 } 00173 00174 SymbolGroundingGraspBasePoseExperimentalResponse_(const ContainerAllocator& _alloc) 00175 : obstacle_check(false) 00176 , reach(0.0) 00177 , grasp_base_pose(_alloc) 00178 { 00179 } 00180 00181 typedef uint8_t _obstacle_check_type; 00182 uint8_t obstacle_check; 00183 00184 typedef float _reach_type; 00185 float reach; 00186 00187 typedef ::geometry_msgs::Pose2D_<ContainerAllocator> _grasp_base_pose_type; 00188 ::geometry_msgs::Pose2D_<ContainerAllocator> grasp_base_pose; 00189 00190 00191 private: 00192 static const char* __s_getDataType_() { return "srs_symbolic_grounding/SymbolGroundingGraspBasePoseExperimentalResponse"; } 00193 public: 00194 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00195 00196 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00197 00198 private: 00199 static const char* __s_getMD5Sum_() { return "1166b4429d4bb491f620326781fed922"; } 00200 public: 00201 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00202 00203 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00204 00205 private: 00206 static const char* __s_getServerMD5Sum_() { return "80365e2dd1e4f246fb4542bfaa7f0518"; } 00207 public: 00208 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00209 00210 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00211 00212 private: 00213 static const char* __s_getMessageDefinition_() { return "bool obstacle_check\n\ 00214 float32 reach\n\ 00215 geometry_msgs/Pose2D grasp_base_pose\n\ 00216 \n\ 00217 \n\ 00218 ================================================================================\n\ 00219 MSG: geometry_msgs/Pose2D\n\ 00220 # This expresses a position and orientation on a 2D manifold.\n\ 00221 \n\ 00222 float64 x\n\ 00223 float64 y\n\ 00224 float64 theta\n\ 00225 "; } 00226 public: 00227 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00228 00229 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00230 00231 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00232 { 00233 ros::serialization::OStream stream(write_ptr, 1000000000); 00234 ros::serialization::serialize(stream, obstacle_check); 00235 ros::serialization::serialize(stream, reach); 00236 ros::serialization::serialize(stream, grasp_base_pose); 00237 return stream.getData(); 00238 } 00239 00240 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00241 { 00242 ros::serialization::IStream stream(read_ptr, 1000000000); 00243 ros::serialization::deserialize(stream, obstacle_check); 00244 ros::serialization::deserialize(stream, reach); 00245 ros::serialization::deserialize(stream, grasp_base_pose); 00246 return stream.getData(); 00247 } 00248 00249 ROS_DEPRECATED virtual uint32_t serializationLength() const 00250 { 00251 uint32_t size = 0; 00252 size += ros::serialization::serializationLength(obstacle_check); 00253 size += ros::serialization::serializationLength(reach); 00254 size += ros::serialization::serializationLength(grasp_base_pose); 00255 return size; 00256 } 00257 00258 typedef boost::shared_ptr< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalResponse_<ContainerAllocator> > Ptr; 00259 typedef boost::shared_ptr< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalResponse_<ContainerAllocator> const> ConstPtr; 00260 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00261 }; // struct SymbolGroundingGraspBasePoseExperimentalResponse 00262 typedef ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalResponse_<std::allocator<void> > SymbolGroundingGraspBasePoseExperimentalResponse; 00263 00264 typedef boost::shared_ptr< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalResponse> SymbolGroundingGraspBasePoseExperimentalResponsePtr; 00265 typedef boost::shared_ptr< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalResponse const> SymbolGroundingGraspBasePoseExperimentalResponseConstPtr; 00266 00267 struct SymbolGroundingGraspBasePoseExperimental 00268 { 00269 00270 typedef SymbolGroundingGraspBasePoseExperimentalRequest Request; 00271 typedef SymbolGroundingGraspBasePoseExperimentalResponse Response; 00272 Request request; 00273 Response response; 00274 00275 typedef Request RequestType; 00276 typedef Response ResponseType; 00277 }; // struct SymbolGroundingGraspBasePoseExperimental 00278 } // namespace srs_symbolic_grounding 00279 00280 namespace ros 00281 { 00282 namespace message_traits 00283 { 00284 template<class ContainerAllocator> struct IsMessage< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalRequest_<ContainerAllocator> > : public TrueType {}; 00285 template<class ContainerAllocator> struct IsMessage< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalRequest_<ContainerAllocator> const> : public TrueType {}; 00286 template<class ContainerAllocator> 00287 struct MD5Sum< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalRequest_<ContainerAllocator> > { 00288 static const char* value() 00289 { 00290 return "929217c873801a8d83a0ef0a0ff55374"; 00291 } 00292 00293 static const char* value(const ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalRequest_<ContainerAllocator> &) { return value(); } 00294 static const uint64_t static_value1 = 0x929217c873801a8dULL; 00295 static const uint64_t static_value2 = 0x83a0ef0a0ff55374ULL; 00296 }; 00297 00298 template<class ContainerAllocator> 00299 struct DataType< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalRequest_<ContainerAllocator> > { 00300 static const char* value() 00301 { 00302 return "srs_symbolic_grounding/SymbolGroundingGraspBasePoseExperimentalRequest"; 00303 } 00304 00305 static const char* value(const ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalRequest_<ContainerAllocator> &) { return value(); } 00306 }; 00307 00308 template<class ContainerAllocator> 00309 struct Definition< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalRequest_<ContainerAllocator> > { 00310 static const char* value() 00311 { 00312 return "geometry_msgs/Pose target_obj_pose\n\ 00313 \n\ 00314 \n\ 00315 srs_msgs/SRSSpatialInfo parent_obj_geometry\n\ 00316 srs_msgs/SRSSpatialInfo[] furniture_geometry_list\n\ 00317 \n\ 00318 ================================================================================\n\ 00319 MSG: geometry_msgs/Pose\n\ 00320 # A representation of pose in free space, composed of postion and orientation. \n\ 00321 Point position\n\ 00322 Quaternion orientation\n\ 00323 \n\ 00324 ================================================================================\n\ 00325 MSG: geometry_msgs/Point\n\ 00326 # This contains the position of a point in free space\n\ 00327 float64 x\n\ 00328 float64 y\n\ 00329 float64 z\n\ 00330 \n\ 00331 ================================================================================\n\ 00332 MSG: geometry_msgs/Quaternion\n\ 00333 # This represents an orientation in free space in quaternion form.\n\ 00334 \n\ 00335 float64 x\n\ 00336 float64 y\n\ 00337 float64 z\n\ 00338 float64 w\n\ 00339 \n\ 00340 ================================================================================\n\ 00341 MSG: srs_msgs/SRSSpatialInfo\n\ 00342 # Point point\n\ 00343 # Orientation angles\n\ 00344 float32 l\n\ 00345 float32 w\n\ 00346 float32 h\n\ 00347 \n\ 00348 geometry_msgs/Pose pose\n\ 00349 \n\ 00350 "; 00351 } 00352 00353 static const char* value(const ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalRequest_<ContainerAllocator> &) { return value(); } 00354 }; 00355 00356 } // namespace message_traits 00357 } // namespace ros 00358 00359 00360 namespace ros 00361 { 00362 namespace message_traits 00363 { 00364 template<class ContainerAllocator> struct IsMessage< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalResponse_<ContainerAllocator> > : public TrueType {}; 00365 template<class ContainerAllocator> struct IsMessage< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalResponse_<ContainerAllocator> const> : public TrueType {}; 00366 template<class ContainerAllocator> 00367 struct MD5Sum< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalResponse_<ContainerAllocator> > { 00368 static const char* value() 00369 { 00370 return "1166b4429d4bb491f620326781fed922"; 00371 } 00372 00373 static const char* value(const ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalResponse_<ContainerAllocator> &) { return value(); } 00374 static const uint64_t static_value1 = 0x1166b4429d4bb491ULL; 00375 static const uint64_t static_value2 = 0xf620326781fed922ULL; 00376 }; 00377 00378 template<class ContainerAllocator> 00379 struct DataType< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalResponse_<ContainerAllocator> > { 00380 static const char* value() 00381 { 00382 return "srs_symbolic_grounding/SymbolGroundingGraspBasePoseExperimentalResponse"; 00383 } 00384 00385 static const char* value(const ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalResponse_<ContainerAllocator> &) { return value(); } 00386 }; 00387 00388 template<class ContainerAllocator> 00389 struct Definition< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalResponse_<ContainerAllocator> > { 00390 static const char* value() 00391 { 00392 return "bool obstacle_check\n\ 00393 float32 reach\n\ 00394 geometry_msgs/Pose2D grasp_base_pose\n\ 00395 \n\ 00396 \n\ 00397 ================================================================================\n\ 00398 MSG: geometry_msgs/Pose2D\n\ 00399 # This expresses a position and orientation on a 2D manifold.\n\ 00400 \n\ 00401 float64 x\n\ 00402 float64 y\n\ 00403 float64 theta\n\ 00404 "; 00405 } 00406 00407 static const char* value(const ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalResponse_<ContainerAllocator> &) { return value(); } 00408 }; 00409 00410 template<class ContainerAllocator> struct IsFixedSize< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalResponse_<ContainerAllocator> > : public TrueType {}; 00411 } // namespace message_traits 00412 } // namespace ros 00413 00414 namespace ros 00415 { 00416 namespace serialization 00417 { 00418 00419 template<class ContainerAllocator> struct Serializer< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalRequest_<ContainerAllocator> > 00420 { 00421 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00422 { 00423 stream.next(m.target_obj_pose); 00424 stream.next(m.parent_obj_geometry); 00425 stream.next(m.furniture_geometry_list); 00426 } 00427 00428 ROS_DECLARE_ALLINONE_SERIALIZER; 00429 }; // struct SymbolGroundingGraspBasePoseExperimentalRequest_ 00430 } // namespace serialization 00431 } // namespace ros 00432 00433 00434 namespace ros 00435 { 00436 namespace serialization 00437 { 00438 00439 template<class ContainerAllocator> struct Serializer< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalResponse_<ContainerAllocator> > 00440 { 00441 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00442 { 00443 stream.next(m.obstacle_check); 00444 stream.next(m.reach); 00445 stream.next(m.grasp_base_pose); 00446 } 00447 00448 ROS_DECLARE_ALLINONE_SERIALIZER; 00449 }; // struct SymbolGroundingGraspBasePoseExperimentalResponse_ 00450 } // namespace serialization 00451 } // namespace ros 00452 00453 namespace ros 00454 { 00455 namespace service_traits 00456 { 00457 template<> 00458 struct MD5Sum<srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimental> { 00459 static const char* value() 00460 { 00461 return "80365e2dd1e4f246fb4542bfaa7f0518"; 00462 } 00463 00464 static const char* value(const srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimental&) { return value(); } 00465 }; 00466 00467 template<> 00468 struct DataType<srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimental> { 00469 static const char* value() 00470 { 00471 return "srs_symbolic_grounding/SymbolGroundingGraspBasePoseExperimental"; 00472 } 00473 00474 static const char* value(const srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimental&) { return value(); } 00475 }; 00476 00477 template<class ContainerAllocator> 00478 struct MD5Sum<srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalRequest_<ContainerAllocator> > { 00479 static const char* value() 00480 { 00481 return "80365e2dd1e4f246fb4542bfaa7f0518"; 00482 } 00483 00484 static const char* value(const srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalRequest_<ContainerAllocator> &) { return value(); } 00485 }; 00486 00487 template<class ContainerAllocator> 00488 struct DataType<srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalRequest_<ContainerAllocator> > { 00489 static const char* value() 00490 { 00491 return "srs_symbolic_grounding/SymbolGroundingGraspBasePoseExperimental"; 00492 } 00493 00494 static const char* value(const srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalRequest_<ContainerAllocator> &) { return value(); } 00495 }; 00496 00497 template<class ContainerAllocator> 00498 struct MD5Sum<srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalResponse_<ContainerAllocator> > { 00499 static const char* value() 00500 { 00501 return "80365e2dd1e4f246fb4542bfaa7f0518"; 00502 } 00503 00504 static const char* value(const srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalResponse_<ContainerAllocator> &) { return value(); } 00505 }; 00506 00507 template<class ContainerAllocator> 00508 struct DataType<srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalResponse_<ContainerAllocator> > { 00509 static const char* value() 00510 { 00511 return "srs_symbolic_grounding/SymbolGroundingGraspBasePoseExperimental"; 00512 } 00513 00514 static const char* value(const srs_symbolic_grounding::SymbolGroundingGraspBasePoseExperimentalResponse_<ContainerAllocator> &) { return value(); } 00515 }; 00516 00517 } // namespace service_traits 00518 } // namespace ros 00519 00520 #endif // SRS_SYMBOLIC_GROUNDING_SERVICE_SYMBOLGROUNDINGGRASPBASEPOSEEXPERIMENTAL_H 00521