GraspAdjust.h
Go to the documentation of this file.
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-fuerte-pr2_object_manipulation/doc_stacks/2014-01-03_11-39-44.427894/pr2_object_manipulation/manipulation/pr2_grasp_adjust/srv/GraspAdjust.srv */
00002 #ifndef PR2_GRASP_ADJUST_SERVICE_GRASPADJUST_H
00003 #define PR2_GRASP_ADJUST_SERVICE_GRASPADJUST_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/PoseStamped.h"
00020 #include "geometry_msgs/Vector3.h"
00021 
00022 
00023 #include "geometry_msgs/PoseStamped.h"
00024 #include "object_manipulation_msgs/ManipulationResult.h"
00025 
00026 namespace pr2_grasp_adjust
00027 {
00028 template <class ContainerAllocator>
00029 struct GraspAdjustRequest_ {
00030   typedef GraspAdjustRequest_<ContainerAllocator> Type;
00031 
00032   GraspAdjustRequest_()
00033   : grasp_pose()
00034   , roi_dims()
00035   , search_mode(0)
00036   {
00037   }
00038 
00039   GraspAdjustRequest_(const ContainerAllocator& _alloc)
00040   : grasp_pose(_alloc)
00041   , roi_dims(_alloc)
00042   , search_mode(0)
00043   {
00044   }
00045 
00046   typedef  ::geometry_msgs::PoseStamped_<ContainerAllocator>  _grasp_pose_type;
00047    ::geometry_msgs::PoseStamped_<ContainerAllocator>  grasp_pose;
00048 
00049   typedef  ::geometry_msgs::Vector3_<ContainerAllocator>  _roi_dims_type;
00050    ::geometry_msgs::Vector3_<ContainerAllocator>  roi_dims;
00051 
00052   typedef uint8_t _search_mode_type;
00053   uint8_t search_mode;
00054 
00055   enum { GLOBAL_SEARCH = 0 };
00056   enum { LOCAL_SEARCH = 1 };
00057   enum { SINGLE_POSE = 2 };
00058 
00059   typedef boost::shared_ptr< ::pr2_grasp_adjust::GraspAdjustRequest_<ContainerAllocator> > Ptr;
00060   typedef boost::shared_ptr< ::pr2_grasp_adjust::GraspAdjustRequest_<ContainerAllocator>  const> ConstPtr;
00061   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00062 }; // struct GraspAdjustRequest
00063 typedef  ::pr2_grasp_adjust::GraspAdjustRequest_<std::allocator<void> > GraspAdjustRequest;
00064 
00065 typedef boost::shared_ptr< ::pr2_grasp_adjust::GraspAdjustRequest> GraspAdjustRequestPtr;
00066 typedef boost::shared_ptr< ::pr2_grasp_adjust::GraspAdjustRequest const> GraspAdjustRequestConstPtr;
00067 
00068 
00069 template <class ContainerAllocator>
00070 struct GraspAdjustResponse_ {
00071   typedef GraspAdjustResponse_<ContainerAllocator> Type;
00072 
00073   GraspAdjustResponse_()
00074   : grasp_poses()
00075   , pose_scores()
00076   , gripper_openings()
00077   , result()
00078   {
00079   }
00080 
00081   GraspAdjustResponse_(const ContainerAllocator& _alloc)
00082   : grasp_poses(_alloc)
00083   , pose_scores(_alloc)
00084   , gripper_openings(_alloc)
00085   , result(_alloc)
00086   {
00087   }
00088 
00089   typedef std::vector< ::geometry_msgs::PoseStamped_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::other >  _grasp_poses_type;
00090   std::vector< ::geometry_msgs::PoseStamped_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::other >  grasp_poses;
00091 
00092   typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other >  _pose_scores_type;
00093   std::vector<double, typename ContainerAllocator::template rebind<double>::other >  pose_scores;
00094 
00095   typedef std::vector<float, typename ContainerAllocator::template rebind<float>::other >  _gripper_openings_type;
00096   std::vector<float, typename ContainerAllocator::template rebind<float>::other >  gripper_openings;
00097 
00098   typedef  ::object_manipulation_msgs::ManipulationResult_<ContainerAllocator>  _result_type;
00099    ::object_manipulation_msgs::ManipulationResult_<ContainerAllocator>  result;
00100 
00101 
00102   typedef boost::shared_ptr< ::pr2_grasp_adjust::GraspAdjustResponse_<ContainerAllocator> > Ptr;
00103   typedef boost::shared_ptr< ::pr2_grasp_adjust::GraspAdjustResponse_<ContainerAllocator>  const> ConstPtr;
00104   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00105 }; // struct GraspAdjustResponse
00106 typedef  ::pr2_grasp_adjust::GraspAdjustResponse_<std::allocator<void> > GraspAdjustResponse;
00107 
00108 typedef boost::shared_ptr< ::pr2_grasp_adjust::GraspAdjustResponse> GraspAdjustResponsePtr;
00109 typedef boost::shared_ptr< ::pr2_grasp_adjust::GraspAdjustResponse const> GraspAdjustResponseConstPtr;
00110 
00111 struct GraspAdjust
00112 {
00113 
00114 typedef GraspAdjustRequest Request;
00115 typedef GraspAdjustResponse Response;
00116 Request request;
00117 Response response;
00118 
00119 typedef Request RequestType;
00120 typedef Response ResponseType;
00121 }; // struct GraspAdjust
00122 } // namespace pr2_grasp_adjust
00123 
00124 namespace ros
00125 {
00126 namespace message_traits
00127 {
00128 template<class ContainerAllocator> struct IsMessage< ::pr2_grasp_adjust::GraspAdjustRequest_<ContainerAllocator> > : public TrueType {};
00129 template<class ContainerAllocator> struct IsMessage< ::pr2_grasp_adjust::GraspAdjustRequest_<ContainerAllocator>  const> : public TrueType {};
00130 template<class ContainerAllocator>
00131 struct MD5Sum< ::pr2_grasp_adjust::GraspAdjustRequest_<ContainerAllocator> > {
00132   static const char* value() 
00133   {
00134     return "e7ccb113bffaf7f7554b005b509b114a";
00135   }
00136 
00137   static const char* value(const  ::pr2_grasp_adjust::GraspAdjustRequest_<ContainerAllocator> &) { return value(); } 
00138   static const uint64_t static_value1 = 0xe7ccb113bffaf7f7ULL;
00139   static const uint64_t static_value2 = 0x554b005b509b114aULL;
00140 };
00141 
00142 template<class ContainerAllocator>
00143 struct DataType< ::pr2_grasp_adjust::GraspAdjustRequest_<ContainerAllocator> > {
00144   static const char* value() 
00145   {
00146     return "pr2_grasp_adjust/GraspAdjustRequest";
00147   }
00148 
00149   static const char* value(const  ::pr2_grasp_adjust::GraspAdjustRequest_<ContainerAllocator> &) { return value(); } 
00150 };
00151 
00152 template<class ContainerAllocator>
00153 struct Definition< ::pr2_grasp_adjust::GraspAdjustRequest_<ContainerAllocator> > {
00154   static const char* value() 
00155   {
00156     return "geometry_msgs/PoseStamped   grasp_pose\n\
00157 geometry_msgs/Vector3       roi_dims\n\
00158 uint8                       search_mode\n\
00159 \n\
00160 int32 GLOBAL_SEARCH = 0\n\
00161 int32 LOCAL_SEARCH = 1\n\
00162 int32 SINGLE_POSE = 2\n\
00163 \n\
00164 \n\
00165 ================================================================================\n\
00166 MSG: geometry_msgs/PoseStamped\n\
00167 # A Pose with reference coordinate frame and timestamp\n\
00168 Header header\n\
00169 Pose pose\n\
00170 \n\
00171 ================================================================================\n\
00172 MSG: std_msgs/Header\n\
00173 # Standard metadata for higher-level stamped data types.\n\
00174 # This is generally used to communicate timestamped data \n\
00175 # in a particular coordinate frame.\n\
00176 # \n\
00177 # sequence ID: consecutively increasing ID \n\
00178 uint32 seq\n\
00179 #Two-integer timestamp that is expressed as:\n\
00180 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00181 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00182 # time-handling sugar is provided by the client library\n\
00183 time stamp\n\
00184 #Frame this data is associated with\n\
00185 # 0: no frame\n\
00186 # 1: global frame\n\
00187 string frame_id\n\
00188 \n\
00189 ================================================================================\n\
00190 MSG: geometry_msgs/Pose\n\
00191 # A representation of pose in free space, composed of postion and orientation. \n\
00192 Point position\n\
00193 Quaternion orientation\n\
00194 \n\
00195 ================================================================================\n\
00196 MSG: geometry_msgs/Point\n\
00197 # This contains the position of a point in free space\n\
00198 float64 x\n\
00199 float64 y\n\
00200 float64 z\n\
00201 \n\
00202 ================================================================================\n\
00203 MSG: geometry_msgs/Quaternion\n\
00204 # This represents an orientation in free space in quaternion form.\n\
00205 \n\
00206 float64 x\n\
00207 float64 y\n\
00208 float64 z\n\
00209 float64 w\n\
00210 \n\
00211 ================================================================================\n\
00212 MSG: geometry_msgs/Vector3\n\
00213 # This represents a vector in free space. \n\
00214 \n\
00215 float64 x\n\
00216 float64 y\n\
00217 float64 z\n\
00218 ";
00219   }
00220 
00221   static const char* value(const  ::pr2_grasp_adjust::GraspAdjustRequest_<ContainerAllocator> &) { return value(); } 
00222 };
00223 
00224 } // namespace message_traits
00225 } // namespace ros
00226 
00227 
00228 namespace ros
00229 {
00230 namespace message_traits
00231 {
00232 template<class ContainerAllocator> struct IsMessage< ::pr2_grasp_adjust::GraspAdjustResponse_<ContainerAllocator> > : public TrueType {};
00233 template<class ContainerAllocator> struct IsMessage< ::pr2_grasp_adjust::GraspAdjustResponse_<ContainerAllocator>  const> : public TrueType {};
00234 template<class ContainerAllocator>
00235 struct MD5Sum< ::pr2_grasp_adjust::GraspAdjustResponse_<ContainerAllocator> > {
00236   static const char* value() 
00237   {
00238     return "8204d8a3e105f84787abc62e550e0312";
00239   }
00240 
00241   static const char* value(const  ::pr2_grasp_adjust::GraspAdjustResponse_<ContainerAllocator> &) { return value(); } 
00242   static const uint64_t static_value1 = 0x8204d8a3e105f847ULL;
00243   static const uint64_t static_value2 = 0x87abc62e550e0312ULL;
00244 };
00245 
00246 template<class ContainerAllocator>
00247 struct DataType< ::pr2_grasp_adjust::GraspAdjustResponse_<ContainerAllocator> > {
00248   static const char* value() 
00249   {
00250     return "pr2_grasp_adjust/GraspAdjustResponse";
00251   }
00252 
00253   static const char* value(const  ::pr2_grasp_adjust::GraspAdjustResponse_<ContainerAllocator> &) { return value(); } 
00254 };
00255 
00256 template<class ContainerAllocator>
00257 struct Definition< ::pr2_grasp_adjust::GraspAdjustResponse_<ContainerAllocator> > {
00258   static const char* value() 
00259   {
00260     return "geometry_msgs/PoseStamped[]  grasp_poses\n\
00261 float64[]  pose_scores\n\
00262 float32[]  gripper_openings\n\
00263 \n\
00264 object_manipulation_msgs/ManipulationResult result\n\
00265 \n\
00266 \n\
00267 \n\
00268 ================================================================================\n\
00269 MSG: geometry_msgs/PoseStamped\n\
00270 # A Pose with reference coordinate frame and timestamp\n\
00271 Header header\n\
00272 Pose pose\n\
00273 \n\
00274 ================================================================================\n\
00275 MSG: std_msgs/Header\n\
00276 # Standard metadata for higher-level stamped data types.\n\
00277 # This is generally used to communicate timestamped data \n\
00278 # in a particular coordinate frame.\n\
00279 # \n\
00280 # sequence ID: consecutively increasing ID \n\
00281 uint32 seq\n\
00282 #Two-integer timestamp that is expressed as:\n\
00283 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00284 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00285 # time-handling sugar is provided by the client library\n\
00286 time stamp\n\
00287 #Frame this data is associated with\n\
00288 # 0: no frame\n\
00289 # 1: global frame\n\
00290 string frame_id\n\
00291 \n\
00292 ================================================================================\n\
00293 MSG: geometry_msgs/Pose\n\
00294 # A representation of pose in free space, composed of postion and orientation. \n\
00295 Point position\n\
00296 Quaternion orientation\n\
00297 \n\
00298 ================================================================================\n\
00299 MSG: geometry_msgs/Point\n\
00300 # This contains the position of a point in free space\n\
00301 float64 x\n\
00302 float64 y\n\
00303 float64 z\n\
00304 \n\
00305 ================================================================================\n\
00306 MSG: geometry_msgs/Quaternion\n\
00307 # This represents an orientation in free space in quaternion form.\n\
00308 \n\
00309 float64 x\n\
00310 float64 y\n\
00311 float64 z\n\
00312 float64 w\n\
00313 \n\
00314 ================================================================================\n\
00315 MSG: object_manipulation_msgs/ManipulationResult\n\
00316 # Result codes for manipulation tasks\n\
00317 \n\
00318 # task completed as expected\n\
00319 # generally means you can proceed as planned\n\
00320 int32 SUCCESS = 1\n\
00321 \n\
00322 # task not possible (e.g. out of reach or obstacles in the way)\n\
00323 # generally means that the world was not disturbed, so you can try another task\n\
00324 int32 UNFEASIBLE = -1\n\
00325 \n\
00326 # task was thought possible, but failed due to unexpected events during execution\n\
00327 # it is likely that the world was disturbed, so you are encouraged to refresh\n\
00328 # your sensed world model before proceeding to another task\n\
00329 int32 FAILED = -2\n\
00330 \n\
00331 # a lower level error prevented task completion (e.g. joint controller not responding)\n\
00332 # generally requires human attention\n\
00333 int32 ERROR = -3\n\
00334 \n\
00335 # means that at some point during execution we ended up in a state that the collision-aware\n\
00336 # arm navigation module will not move out of. The world was likely not disturbed, but you \n\
00337 # probably need a new collision map to move the arm out of the stuck position\n\
00338 int32 ARM_MOVEMENT_PREVENTED = -4\n\
00339 \n\
00340 # specific to grasp actions\n\
00341 # the object was grasped successfully, but the lift attempt could not achieve the minimum lift distance requested\n\
00342 # it is likely that the collision environment will see collisions between the hand/object and the support surface\n\
00343 int32 LIFT_FAILED = -5\n\
00344 \n\
00345 # specific to place actions\n\
00346 # the object was placed successfully, but the retreat attempt could not achieve the minimum retreat distance requested\n\
00347 # it is likely that the collision environment will see collisions between the hand and the object\n\
00348 int32 RETREAT_FAILED = -6\n\
00349 \n\
00350 # indicates that somewhere along the line a human said \"wait, stop, this is bad, go back and do something else\"\n\
00351 int32 CANCELLED = -7\n\
00352 \n\
00353 # the actual value of this error code\n\
00354 int32 value\n\
00355 \n\
00356 ";
00357   }
00358 
00359   static const char* value(const  ::pr2_grasp_adjust::GraspAdjustResponse_<ContainerAllocator> &) { return value(); } 
00360 };
00361 
00362 } // namespace message_traits
00363 } // namespace ros
00364 
00365 namespace ros
00366 {
00367 namespace serialization
00368 {
00369 
00370 template<class ContainerAllocator> struct Serializer< ::pr2_grasp_adjust::GraspAdjustRequest_<ContainerAllocator> >
00371 {
00372   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00373   {
00374     stream.next(m.grasp_pose);
00375     stream.next(m.roi_dims);
00376     stream.next(m.search_mode);
00377   }
00378 
00379   ROS_DECLARE_ALLINONE_SERIALIZER;
00380 }; // struct GraspAdjustRequest_
00381 } // namespace serialization
00382 } // namespace ros
00383 
00384 
00385 namespace ros
00386 {
00387 namespace serialization
00388 {
00389 
00390 template<class ContainerAllocator> struct Serializer< ::pr2_grasp_adjust::GraspAdjustResponse_<ContainerAllocator> >
00391 {
00392   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00393   {
00394     stream.next(m.grasp_poses);
00395     stream.next(m.pose_scores);
00396     stream.next(m.gripper_openings);
00397     stream.next(m.result);
00398   }
00399 
00400   ROS_DECLARE_ALLINONE_SERIALIZER;
00401 }; // struct GraspAdjustResponse_
00402 } // namespace serialization
00403 } // namespace ros
00404 
00405 namespace ros
00406 {
00407 namespace service_traits
00408 {
00409 template<>
00410 struct MD5Sum<pr2_grasp_adjust::GraspAdjust> {
00411   static const char* value() 
00412   {
00413     return "155f94ed302ff095096df9b37ecc7886";
00414   }
00415 
00416   static const char* value(const pr2_grasp_adjust::GraspAdjust&) { return value(); } 
00417 };
00418 
00419 template<>
00420 struct DataType<pr2_grasp_adjust::GraspAdjust> {
00421   static const char* value() 
00422   {
00423     return "pr2_grasp_adjust/GraspAdjust";
00424   }
00425 
00426   static const char* value(const pr2_grasp_adjust::GraspAdjust&) { return value(); } 
00427 };
00428 
00429 template<class ContainerAllocator>
00430 struct MD5Sum<pr2_grasp_adjust::GraspAdjustRequest_<ContainerAllocator> > {
00431   static const char* value() 
00432   {
00433     return "155f94ed302ff095096df9b37ecc7886";
00434   }
00435 
00436   static const char* value(const pr2_grasp_adjust::GraspAdjustRequest_<ContainerAllocator> &) { return value(); } 
00437 };
00438 
00439 template<class ContainerAllocator>
00440 struct DataType<pr2_grasp_adjust::GraspAdjustRequest_<ContainerAllocator> > {
00441   static const char* value() 
00442   {
00443     return "pr2_grasp_adjust/GraspAdjust";
00444   }
00445 
00446   static const char* value(const pr2_grasp_adjust::GraspAdjustRequest_<ContainerAllocator> &) { return value(); } 
00447 };
00448 
00449 template<class ContainerAllocator>
00450 struct MD5Sum<pr2_grasp_adjust::GraspAdjustResponse_<ContainerAllocator> > {
00451   static const char* value() 
00452   {
00453     return "155f94ed302ff095096df9b37ecc7886";
00454   }
00455 
00456   static const char* value(const pr2_grasp_adjust::GraspAdjustResponse_<ContainerAllocator> &) { return value(); } 
00457 };
00458 
00459 template<class ContainerAllocator>
00460 struct DataType<pr2_grasp_adjust::GraspAdjustResponse_<ContainerAllocator> > {
00461   static const char* value() 
00462   {
00463     return "pr2_grasp_adjust/GraspAdjust";
00464   }
00465 
00466   static const char* value(const pr2_grasp_adjust::GraspAdjustResponse_<ContainerAllocator> &) { return value(); } 
00467 };
00468 
00469 } // namespace service_traits
00470 } // namespace ros
00471 
00472 #endif // PR2_GRASP_ADJUST_SERVICE_GRASPADJUST_H
00473 


pr2_grasp_adjust
Author(s): Adam Leeper
autogenerated on Fri Jan 3 2014 12:00:29