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