$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_grasping/srv/GetFeasibleGrasps.srv */ 00002 #ifndef SRS_GRASPING_SERVICE_GETFEASIBLEGRASPS_H 00003 #define SRS_GRASPING_SERVICE_GETFEASIBLEGRASPS_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 #include "srs_msgs/FeasibleGrasp.h" 00023 #include "srs_msgs/GraspingErrorCodes.h" 00024 00025 namespace srs_grasping 00026 { 00027 template <class ContainerAllocator> 00028 struct GetFeasibleGraspsRequest_ { 00029 typedef GetFeasibleGraspsRequest_<ContainerAllocator> Type; 00030 00031 GetFeasibleGraspsRequest_() 00032 : object_id(0) 00033 , object_pose() 00034 , pregrasp_offsets() 00035 { 00036 } 00037 00038 GetFeasibleGraspsRequest_(const ContainerAllocator& _alloc) 00039 : object_id(0) 00040 , object_pose(_alloc) 00041 , pregrasp_offsets(_alloc) 00042 { 00043 } 00044 00045 typedef int32_t _object_id_type; 00046 int32_t object_id; 00047 00048 typedef ::geometry_msgs::Pose_<ContainerAllocator> _object_pose_type; 00049 ::geometry_msgs::Pose_<ContainerAllocator> object_pose; 00050 00051 typedef std::vector<float, typename ContainerAllocator::template rebind<float>::other > _pregrasp_offsets_type; 00052 std::vector<float, typename ContainerAllocator::template rebind<float>::other > pregrasp_offsets; 00053 00054 00055 ROS_DEPRECATED uint32_t get_pregrasp_offsets_size() const { return (uint32_t)pregrasp_offsets.size(); } 00056 ROS_DEPRECATED void set_pregrasp_offsets_size(uint32_t size) { pregrasp_offsets.resize((size_t)size); } 00057 ROS_DEPRECATED void get_pregrasp_offsets_vec(std::vector<float, typename ContainerAllocator::template rebind<float>::other > & vec) const { vec = this->pregrasp_offsets; } 00058 ROS_DEPRECATED void set_pregrasp_offsets_vec(const std::vector<float, typename ContainerAllocator::template rebind<float>::other > & vec) { this->pregrasp_offsets = vec; } 00059 private: 00060 static const char* __s_getDataType_() { return "srs_grasping/GetFeasibleGraspsRequest"; } 00061 public: 00062 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00063 00064 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00065 00066 private: 00067 static const char* __s_getMD5Sum_() { return "2f992715efcc4a20cb1f1eaaa8982d56"; } 00068 public: 00069 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00070 00071 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00072 00073 private: 00074 static const char* __s_getServerMD5Sum_() { return "784b27be1f50ac2f91c4f1ce4b6ad528"; } 00075 public: 00076 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00077 00078 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00079 00080 private: 00081 static const char* __s_getMessageDefinition_() { return "int32 object_id\n\ 00082 geometry_msgs/Pose object_pose\n\ 00083 float32[] pregrasp_offsets\n\ 00084 \n\ 00085 ================================================================================\n\ 00086 MSG: geometry_msgs/Pose\n\ 00087 # A representation of pose in free space, composed of postion and orientation. \n\ 00088 Point position\n\ 00089 Quaternion orientation\n\ 00090 \n\ 00091 ================================================================================\n\ 00092 MSG: geometry_msgs/Point\n\ 00093 # This contains the position of a point in free space\n\ 00094 float64 x\n\ 00095 float64 y\n\ 00096 float64 z\n\ 00097 \n\ 00098 ================================================================================\n\ 00099 MSG: geometry_msgs/Quaternion\n\ 00100 # This represents an orientation in free space in quaternion form.\n\ 00101 \n\ 00102 float64 x\n\ 00103 float64 y\n\ 00104 float64 z\n\ 00105 float64 w\n\ 00106 \n\ 00107 "; } 00108 public: 00109 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00110 00111 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00112 00113 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00114 { 00115 ros::serialization::OStream stream(write_ptr, 1000000000); 00116 ros::serialization::serialize(stream, object_id); 00117 ros::serialization::serialize(stream, object_pose); 00118 ros::serialization::serialize(stream, pregrasp_offsets); 00119 return stream.getData(); 00120 } 00121 00122 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00123 { 00124 ros::serialization::IStream stream(read_ptr, 1000000000); 00125 ros::serialization::deserialize(stream, object_id); 00126 ros::serialization::deserialize(stream, object_pose); 00127 ros::serialization::deserialize(stream, pregrasp_offsets); 00128 return stream.getData(); 00129 } 00130 00131 ROS_DEPRECATED virtual uint32_t serializationLength() const 00132 { 00133 uint32_t size = 0; 00134 size += ros::serialization::serializationLength(object_id); 00135 size += ros::serialization::serializationLength(object_pose); 00136 size += ros::serialization::serializationLength(pregrasp_offsets); 00137 return size; 00138 } 00139 00140 typedef boost::shared_ptr< ::srs_grasping::GetFeasibleGraspsRequest_<ContainerAllocator> > Ptr; 00141 typedef boost::shared_ptr< ::srs_grasping::GetFeasibleGraspsRequest_<ContainerAllocator> const> ConstPtr; 00142 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00143 }; // struct GetFeasibleGraspsRequest 00144 typedef ::srs_grasping::GetFeasibleGraspsRequest_<std::allocator<void> > GetFeasibleGraspsRequest; 00145 00146 typedef boost::shared_ptr< ::srs_grasping::GetFeasibleGraspsRequest> GetFeasibleGraspsRequestPtr; 00147 typedef boost::shared_ptr< ::srs_grasping::GetFeasibleGraspsRequest const> GetFeasibleGraspsRequestConstPtr; 00148 00149 00150 template <class ContainerAllocator> 00151 struct GetFeasibleGraspsResponse_ { 00152 typedef GetFeasibleGraspsResponse_<ContainerAllocator> Type; 00153 00154 GetFeasibleGraspsResponse_() 00155 : feasible_grasp_available(false) 00156 , grasp_configuration() 00157 , error_code() 00158 { 00159 } 00160 00161 GetFeasibleGraspsResponse_(const ContainerAllocator& _alloc) 00162 : feasible_grasp_available(false) 00163 , grasp_configuration(_alloc) 00164 , error_code(_alloc) 00165 { 00166 } 00167 00168 typedef uint8_t _feasible_grasp_available_type; 00169 uint8_t feasible_grasp_available; 00170 00171 typedef std::vector< ::srs_msgs::FeasibleGrasp_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::srs_msgs::FeasibleGrasp_<ContainerAllocator> >::other > _grasp_configuration_type; 00172 std::vector< ::srs_msgs::FeasibleGrasp_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::srs_msgs::FeasibleGrasp_<ContainerAllocator> >::other > grasp_configuration; 00173 00174 typedef ::srs_msgs::GraspingErrorCodes_<ContainerAllocator> _error_code_type; 00175 ::srs_msgs::GraspingErrorCodes_<ContainerAllocator> error_code; 00176 00177 00178 ROS_DEPRECATED uint32_t get_grasp_configuration_size() const { return (uint32_t)grasp_configuration.size(); } 00179 ROS_DEPRECATED void set_grasp_configuration_size(uint32_t size) { grasp_configuration.resize((size_t)size); } 00180 ROS_DEPRECATED void get_grasp_configuration_vec(std::vector< ::srs_msgs::FeasibleGrasp_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::srs_msgs::FeasibleGrasp_<ContainerAllocator> >::other > & vec) const { vec = this->grasp_configuration; } 00181 ROS_DEPRECATED void set_grasp_configuration_vec(const std::vector< ::srs_msgs::FeasibleGrasp_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::srs_msgs::FeasibleGrasp_<ContainerAllocator> >::other > & vec) { this->grasp_configuration = vec; } 00182 private: 00183 static const char* __s_getDataType_() { return "srs_grasping/GetFeasibleGraspsResponse"; } 00184 public: 00185 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00186 00187 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00188 00189 private: 00190 static const char* __s_getMD5Sum_() { return "cc5caf9c9653f4aec8db6f1a617e1589"; } 00191 public: 00192 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00193 00194 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00195 00196 private: 00197 static const char* __s_getServerMD5Sum_() { return "784b27be1f50ac2f91c4f1ce4b6ad528"; } 00198 public: 00199 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00200 00201 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00202 00203 private: 00204 static const char* __s_getMessageDefinition_() { return "bool feasible_grasp_available\n\ 00205 srs_msgs/FeasibleGrasp[] grasp_configuration\n\ 00206 srs_msgs/GraspingErrorCodes error_code\n\ 00207 \n\ 00208 \n\ 00209 ================================================================================\n\ 00210 MSG: srs_msgs/FeasibleGrasp\n\ 00211 float64[] sdh_joint_values\n\ 00212 string target_link #link which should be moved to pre_grasp (e.g. sdh_palm_link)\n\ 00213 geometry_msgs/PoseStamped grasp\n\ 00214 geometry_msgs/PoseStamped pre_grasp\n\ 00215 string category\n\ 00216 \n\ 00217 ================================================================================\n\ 00218 MSG: geometry_msgs/PoseStamped\n\ 00219 # A Pose with reference coordinate frame and timestamp\n\ 00220 Header header\n\ 00221 Pose pose\n\ 00222 \n\ 00223 ================================================================================\n\ 00224 MSG: std_msgs/Header\n\ 00225 # Standard metadata for higher-level stamped data types.\n\ 00226 # This is generally used to communicate timestamped data \n\ 00227 # in a particular coordinate frame.\n\ 00228 # \n\ 00229 # sequence ID: consecutively increasing ID \n\ 00230 uint32 seq\n\ 00231 #Two-integer timestamp that is expressed as:\n\ 00232 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00233 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00234 # time-handling sugar is provided by the client library\n\ 00235 time stamp\n\ 00236 #Frame this data is associated with\n\ 00237 # 0: no frame\n\ 00238 # 1: global frame\n\ 00239 string frame_id\n\ 00240 \n\ 00241 ================================================================================\n\ 00242 MSG: geometry_msgs/Pose\n\ 00243 # A representation of pose in free space, composed of postion and orientation. \n\ 00244 Point position\n\ 00245 Quaternion orientation\n\ 00246 \n\ 00247 ================================================================================\n\ 00248 MSG: geometry_msgs/Point\n\ 00249 # This contains the position of a point in free space\n\ 00250 float64 x\n\ 00251 float64 y\n\ 00252 float64 z\n\ 00253 \n\ 00254 ================================================================================\n\ 00255 MSG: geometry_msgs/Quaternion\n\ 00256 # This represents an orientation in free space in quaternion form.\n\ 00257 \n\ 00258 float64 x\n\ 00259 float64 y\n\ 00260 float64 z\n\ 00261 float64 w\n\ 00262 \n\ 00263 ================================================================================\n\ 00264 MSG: srs_msgs/GraspingErrorCodes\n\ 00265 int32 val\n\ 00266 \n\ 00267 int32 SUCCESS=1\n\ 00268 int32 SERVICE_DID_NOT_PROCESS_REQUEST=-1\n\ 00269 int32 UNKNOWN_OBJECT=-2\n\ 00270 int32 CORRUPTED_MESH_FILE=-3\n\ 00271 int32 CORRUPTED_ROBOT_MESH_FILE=-4\n\ 00272 int32 CORRUPTED_GRASP_FILE=-5\n\ 00273 int32 NON_GENERATED_INFO=-6\n\ 00274 int32 OBJECT_INFO_NOT_FOUND=-7\n\ 00275 int32 UNKNOWN_CATEGORY=-8\n\ 00276 int32 GOAL_UNREACHABLE=-9\n\ 00277 \n\ 00278 "; } 00279 public: 00280 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00281 00282 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00283 00284 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00285 { 00286 ros::serialization::OStream stream(write_ptr, 1000000000); 00287 ros::serialization::serialize(stream, feasible_grasp_available); 00288 ros::serialization::serialize(stream, grasp_configuration); 00289 ros::serialization::serialize(stream, error_code); 00290 return stream.getData(); 00291 } 00292 00293 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00294 { 00295 ros::serialization::IStream stream(read_ptr, 1000000000); 00296 ros::serialization::deserialize(stream, feasible_grasp_available); 00297 ros::serialization::deserialize(stream, grasp_configuration); 00298 ros::serialization::deserialize(stream, error_code); 00299 return stream.getData(); 00300 } 00301 00302 ROS_DEPRECATED virtual uint32_t serializationLength() const 00303 { 00304 uint32_t size = 0; 00305 size += ros::serialization::serializationLength(feasible_grasp_available); 00306 size += ros::serialization::serializationLength(grasp_configuration); 00307 size += ros::serialization::serializationLength(error_code); 00308 return size; 00309 } 00310 00311 typedef boost::shared_ptr< ::srs_grasping::GetFeasibleGraspsResponse_<ContainerAllocator> > Ptr; 00312 typedef boost::shared_ptr< ::srs_grasping::GetFeasibleGraspsResponse_<ContainerAllocator> const> ConstPtr; 00313 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00314 }; // struct GetFeasibleGraspsResponse 00315 typedef ::srs_grasping::GetFeasibleGraspsResponse_<std::allocator<void> > GetFeasibleGraspsResponse; 00316 00317 typedef boost::shared_ptr< ::srs_grasping::GetFeasibleGraspsResponse> GetFeasibleGraspsResponsePtr; 00318 typedef boost::shared_ptr< ::srs_grasping::GetFeasibleGraspsResponse const> GetFeasibleGraspsResponseConstPtr; 00319 00320 struct GetFeasibleGrasps 00321 { 00322 00323 typedef GetFeasibleGraspsRequest Request; 00324 typedef GetFeasibleGraspsResponse Response; 00325 Request request; 00326 Response response; 00327 00328 typedef Request RequestType; 00329 typedef Response ResponseType; 00330 }; // struct GetFeasibleGrasps 00331 } // namespace srs_grasping 00332 00333 namespace ros 00334 { 00335 namespace message_traits 00336 { 00337 template<class ContainerAllocator> struct IsMessage< ::srs_grasping::GetFeasibleGraspsRequest_<ContainerAllocator> > : public TrueType {}; 00338 template<class ContainerAllocator> struct IsMessage< ::srs_grasping::GetFeasibleGraspsRequest_<ContainerAllocator> const> : public TrueType {}; 00339 template<class ContainerAllocator> 00340 struct MD5Sum< ::srs_grasping::GetFeasibleGraspsRequest_<ContainerAllocator> > { 00341 static const char* value() 00342 { 00343 return "2f992715efcc4a20cb1f1eaaa8982d56"; 00344 } 00345 00346 static const char* value(const ::srs_grasping::GetFeasibleGraspsRequest_<ContainerAllocator> &) { return value(); } 00347 static const uint64_t static_value1 = 0x2f992715efcc4a20ULL; 00348 static const uint64_t static_value2 = 0xcb1f1eaaa8982d56ULL; 00349 }; 00350 00351 template<class ContainerAllocator> 00352 struct DataType< ::srs_grasping::GetFeasibleGraspsRequest_<ContainerAllocator> > { 00353 static const char* value() 00354 { 00355 return "srs_grasping/GetFeasibleGraspsRequest"; 00356 } 00357 00358 static const char* value(const ::srs_grasping::GetFeasibleGraspsRequest_<ContainerAllocator> &) { return value(); } 00359 }; 00360 00361 template<class ContainerAllocator> 00362 struct Definition< ::srs_grasping::GetFeasibleGraspsRequest_<ContainerAllocator> > { 00363 static const char* value() 00364 { 00365 return "int32 object_id\n\ 00366 geometry_msgs/Pose object_pose\n\ 00367 float32[] pregrasp_offsets\n\ 00368 \n\ 00369 ================================================================================\n\ 00370 MSG: geometry_msgs/Pose\n\ 00371 # A representation of pose in free space, composed of postion and orientation. \n\ 00372 Point position\n\ 00373 Quaternion orientation\n\ 00374 \n\ 00375 ================================================================================\n\ 00376 MSG: geometry_msgs/Point\n\ 00377 # This contains the position of a point in free space\n\ 00378 float64 x\n\ 00379 float64 y\n\ 00380 float64 z\n\ 00381 \n\ 00382 ================================================================================\n\ 00383 MSG: geometry_msgs/Quaternion\n\ 00384 # This represents an orientation in free space in quaternion form.\n\ 00385 \n\ 00386 float64 x\n\ 00387 float64 y\n\ 00388 float64 z\n\ 00389 float64 w\n\ 00390 \n\ 00391 "; 00392 } 00393 00394 static const char* value(const ::srs_grasping::GetFeasibleGraspsRequest_<ContainerAllocator> &) { return value(); } 00395 }; 00396 00397 } // namespace message_traits 00398 } // namespace ros 00399 00400 00401 namespace ros 00402 { 00403 namespace message_traits 00404 { 00405 template<class ContainerAllocator> struct IsMessage< ::srs_grasping::GetFeasibleGraspsResponse_<ContainerAllocator> > : public TrueType {}; 00406 template<class ContainerAllocator> struct IsMessage< ::srs_grasping::GetFeasibleGraspsResponse_<ContainerAllocator> const> : public TrueType {}; 00407 template<class ContainerAllocator> 00408 struct MD5Sum< ::srs_grasping::GetFeasibleGraspsResponse_<ContainerAllocator> > { 00409 static const char* value() 00410 { 00411 return "cc5caf9c9653f4aec8db6f1a617e1589"; 00412 } 00413 00414 static const char* value(const ::srs_grasping::GetFeasibleGraspsResponse_<ContainerAllocator> &) { return value(); } 00415 static const uint64_t static_value1 = 0xcc5caf9c9653f4aeULL; 00416 static const uint64_t static_value2 = 0xc8db6f1a617e1589ULL; 00417 }; 00418 00419 template<class ContainerAllocator> 00420 struct DataType< ::srs_grasping::GetFeasibleGraspsResponse_<ContainerAllocator> > { 00421 static const char* value() 00422 { 00423 return "srs_grasping/GetFeasibleGraspsResponse"; 00424 } 00425 00426 static const char* value(const ::srs_grasping::GetFeasibleGraspsResponse_<ContainerAllocator> &) { return value(); } 00427 }; 00428 00429 template<class ContainerAllocator> 00430 struct Definition< ::srs_grasping::GetFeasibleGraspsResponse_<ContainerAllocator> > { 00431 static const char* value() 00432 { 00433 return "bool feasible_grasp_available\n\ 00434 srs_msgs/FeasibleGrasp[] grasp_configuration\n\ 00435 srs_msgs/GraspingErrorCodes error_code\n\ 00436 \n\ 00437 \n\ 00438 ================================================================================\n\ 00439 MSG: srs_msgs/FeasibleGrasp\n\ 00440 float64[] sdh_joint_values\n\ 00441 string target_link #link which should be moved to pre_grasp (e.g. sdh_palm_link)\n\ 00442 geometry_msgs/PoseStamped grasp\n\ 00443 geometry_msgs/PoseStamped pre_grasp\n\ 00444 string category\n\ 00445 \n\ 00446 ================================================================================\n\ 00447 MSG: geometry_msgs/PoseStamped\n\ 00448 # A Pose with reference coordinate frame and timestamp\n\ 00449 Header header\n\ 00450 Pose pose\n\ 00451 \n\ 00452 ================================================================================\n\ 00453 MSG: std_msgs/Header\n\ 00454 # Standard metadata for higher-level stamped data types.\n\ 00455 # This is generally used to communicate timestamped data \n\ 00456 # in a particular coordinate frame.\n\ 00457 # \n\ 00458 # sequence ID: consecutively increasing ID \n\ 00459 uint32 seq\n\ 00460 #Two-integer timestamp that is expressed as:\n\ 00461 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00462 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00463 # time-handling sugar is provided by the client library\n\ 00464 time stamp\n\ 00465 #Frame this data is associated with\n\ 00466 # 0: no frame\n\ 00467 # 1: global frame\n\ 00468 string frame_id\n\ 00469 \n\ 00470 ================================================================================\n\ 00471 MSG: geometry_msgs/Pose\n\ 00472 # A representation of pose in free space, composed of postion and orientation. \n\ 00473 Point position\n\ 00474 Quaternion orientation\n\ 00475 \n\ 00476 ================================================================================\n\ 00477 MSG: geometry_msgs/Point\n\ 00478 # This contains the position of a point in free space\n\ 00479 float64 x\n\ 00480 float64 y\n\ 00481 float64 z\n\ 00482 \n\ 00483 ================================================================================\n\ 00484 MSG: geometry_msgs/Quaternion\n\ 00485 # This represents an orientation in free space in quaternion form.\n\ 00486 \n\ 00487 float64 x\n\ 00488 float64 y\n\ 00489 float64 z\n\ 00490 float64 w\n\ 00491 \n\ 00492 ================================================================================\n\ 00493 MSG: srs_msgs/GraspingErrorCodes\n\ 00494 int32 val\n\ 00495 \n\ 00496 int32 SUCCESS=1\n\ 00497 int32 SERVICE_DID_NOT_PROCESS_REQUEST=-1\n\ 00498 int32 UNKNOWN_OBJECT=-2\n\ 00499 int32 CORRUPTED_MESH_FILE=-3\n\ 00500 int32 CORRUPTED_ROBOT_MESH_FILE=-4\n\ 00501 int32 CORRUPTED_GRASP_FILE=-5\n\ 00502 int32 NON_GENERATED_INFO=-6\n\ 00503 int32 OBJECT_INFO_NOT_FOUND=-7\n\ 00504 int32 UNKNOWN_CATEGORY=-8\n\ 00505 int32 GOAL_UNREACHABLE=-9\n\ 00506 \n\ 00507 "; 00508 } 00509 00510 static const char* value(const ::srs_grasping::GetFeasibleGraspsResponse_<ContainerAllocator> &) { return value(); } 00511 }; 00512 00513 } // namespace message_traits 00514 } // namespace ros 00515 00516 namespace ros 00517 { 00518 namespace serialization 00519 { 00520 00521 template<class ContainerAllocator> struct Serializer< ::srs_grasping::GetFeasibleGraspsRequest_<ContainerAllocator> > 00522 { 00523 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00524 { 00525 stream.next(m.object_id); 00526 stream.next(m.object_pose); 00527 stream.next(m.pregrasp_offsets); 00528 } 00529 00530 ROS_DECLARE_ALLINONE_SERIALIZER; 00531 }; // struct GetFeasibleGraspsRequest_ 00532 } // namespace serialization 00533 } // namespace ros 00534 00535 00536 namespace ros 00537 { 00538 namespace serialization 00539 { 00540 00541 template<class ContainerAllocator> struct Serializer< ::srs_grasping::GetFeasibleGraspsResponse_<ContainerAllocator> > 00542 { 00543 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00544 { 00545 stream.next(m.feasible_grasp_available); 00546 stream.next(m.grasp_configuration); 00547 stream.next(m.error_code); 00548 } 00549 00550 ROS_DECLARE_ALLINONE_SERIALIZER; 00551 }; // struct GetFeasibleGraspsResponse_ 00552 } // namespace serialization 00553 } // namespace ros 00554 00555 namespace ros 00556 { 00557 namespace service_traits 00558 { 00559 template<> 00560 struct MD5Sum<srs_grasping::GetFeasibleGrasps> { 00561 static const char* value() 00562 { 00563 return "784b27be1f50ac2f91c4f1ce4b6ad528"; 00564 } 00565 00566 static const char* value(const srs_grasping::GetFeasibleGrasps&) { return value(); } 00567 }; 00568 00569 template<> 00570 struct DataType<srs_grasping::GetFeasibleGrasps> { 00571 static const char* value() 00572 { 00573 return "srs_grasping/GetFeasibleGrasps"; 00574 } 00575 00576 static const char* value(const srs_grasping::GetFeasibleGrasps&) { return value(); } 00577 }; 00578 00579 template<class ContainerAllocator> 00580 struct MD5Sum<srs_grasping::GetFeasibleGraspsRequest_<ContainerAllocator> > { 00581 static const char* value() 00582 { 00583 return "784b27be1f50ac2f91c4f1ce4b6ad528"; 00584 } 00585 00586 static const char* value(const srs_grasping::GetFeasibleGraspsRequest_<ContainerAllocator> &) { return value(); } 00587 }; 00588 00589 template<class ContainerAllocator> 00590 struct DataType<srs_grasping::GetFeasibleGraspsRequest_<ContainerAllocator> > { 00591 static const char* value() 00592 { 00593 return "srs_grasping/GetFeasibleGrasps"; 00594 } 00595 00596 static const char* value(const srs_grasping::GetFeasibleGraspsRequest_<ContainerAllocator> &) { return value(); } 00597 }; 00598 00599 template<class ContainerAllocator> 00600 struct MD5Sum<srs_grasping::GetFeasibleGraspsResponse_<ContainerAllocator> > { 00601 static const char* value() 00602 { 00603 return "784b27be1f50ac2f91c4f1ce4b6ad528"; 00604 } 00605 00606 static const char* value(const srs_grasping::GetFeasibleGraspsResponse_<ContainerAllocator> &) { return value(); } 00607 }; 00608 00609 template<class ContainerAllocator> 00610 struct DataType<srs_grasping::GetFeasibleGraspsResponse_<ContainerAllocator> > { 00611 static const char* value() 00612 { 00613 return "srs_grasping/GetFeasibleGrasps"; 00614 } 00615 00616 static const char* value(const srs_grasping::GetFeasibleGraspsResponse_<ContainerAllocator> &) { return value(); } 00617 }; 00618 00619 } // namespace service_traits 00620 } // namespace ros 00621 00622 #endif // SRS_GRASPING_SERVICE_GETFEASIBLEGRASPS_H 00623