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