GetGripperPoseGoal.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_object_manipulation_msgs/msg/GetGripperPoseGoal.msg */
00002 #ifndef PR2_OBJECT_MANIPULATION_MSGS_MESSAGE_GETGRIPPERPOSEGOAL_H
00003 #define PR2_OBJECT_MANIPULATION_MSGS_MESSAGE_GETGRIPPERPOSEGOAL_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 "geometry_msgs/PoseStamped.h"
00018 #include "object_manipulation_msgs/GraspableObject.h"
00019 #include "object_manipulation_msgs/Grasp.h"
00020 
00021 namespace pr2_object_manipulation_msgs
00022 {
00023 template <class ContainerAllocator>
00024 struct GetGripperPoseGoal_ {
00025   typedef GetGripperPoseGoal_<ContainerAllocator> Type;
00026 
00027   GetGripperPoseGoal_()
00028   : arm_name()
00029   , gripper_pose()
00030   , gripper_opening(0.0)
00031   , object()
00032   , grasp()
00033   {
00034   }
00035 
00036   GetGripperPoseGoal_(const ContainerAllocator& _alloc)
00037   : arm_name(_alloc)
00038   , gripper_pose(_alloc)
00039   , gripper_opening(0.0)
00040   , object(_alloc)
00041   , grasp(_alloc)
00042   {
00043   }
00044 
00045   typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  _arm_name_type;
00046   std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  arm_name;
00047 
00048   typedef  ::geometry_msgs::PoseStamped_<ContainerAllocator>  _gripper_pose_type;
00049    ::geometry_msgs::PoseStamped_<ContainerAllocator>  gripper_pose;
00050 
00051   typedef float _gripper_opening_type;
00052   float gripper_opening;
00053 
00054   typedef  ::object_manipulation_msgs::GraspableObject_<ContainerAllocator>  _object_type;
00055    ::object_manipulation_msgs::GraspableObject_<ContainerAllocator>  object;
00056 
00057   typedef  ::object_manipulation_msgs::Grasp_<ContainerAllocator>  _grasp_type;
00058    ::object_manipulation_msgs::Grasp_<ContainerAllocator>  grasp;
00059 
00060 
00061   typedef boost::shared_ptr< ::pr2_object_manipulation_msgs::GetGripperPoseGoal_<ContainerAllocator> > Ptr;
00062   typedef boost::shared_ptr< ::pr2_object_manipulation_msgs::GetGripperPoseGoal_<ContainerAllocator>  const> ConstPtr;
00063   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00064 }; // struct GetGripperPoseGoal
00065 typedef  ::pr2_object_manipulation_msgs::GetGripperPoseGoal_<std::allocator<void> > GetGripperPoseGoal;
00066 
00067 typedef boost::shared_ptr< ::pr2_object_manipulation_msgs::GetGripperPoseGoal> GetGripperPoseGoalPtr;
00068 typedef boost::shared_ptr< ::pr2_object_manipulation_msgs::GetGripperPoseGoal const> GetGripperPoseGoalConstPtr;
00069 
00070 
00071 template<typename ContainerAllocator>
00072 std::ostream& operator<<(std::ostream& s, const  ::pr2_object_manipulation_msgs::GetGripperPoseGoal_<ContainerAllocator> & v)
00073 {
00074   ros::message_operations::Printer< ::pr2_object_manipulation_msgs::GetGripperPoseGoal_<ContainerAllocator> >::stream(s, "", v);
00075   return s;}
00076 
00077 } // namespace pr2_object_manipulation_msgs
00078 
00079 namespace ros
00080 {
00081 namespace message_traits
00082 {
00083 template<class ContainerAllocator> struct IsMessage< ::pr2_object_manipulation_msgs::GetGripperPoseGoal_<ContainerAllocator> > : public TrueType {};
00084 template<class ContainerAllocator> struct IsMessage< ::pr2_object_manipulation_msgs::GetGripperPoseGoal_<ContainerAllocator>  const> : public TrueType {};
00085 template<class ContainerAllocator>
00086 struct MD5Sum< ::pr2_object_manipulation_msgs::GetGripperPoseGoal_<ContainerAllocator> > {
00087   static const char* value() 
00088   {
00089     return "7ca516fef9c15991c035b01ff6268377";
00090   }
00091 
00092   static const char* value(const  ::pr2_object_manipulation_msgs::GetGripperPoseGoal_<ContainerAllocator> &) { return value(); } 
00093   static const uint64_t static_value1 = 0x7ca516fef9c15991ULL;
00094   static const uint64_t static_value2 = 0xc035b01ff6268377ULL;
00095 };
00096 
00097 template<class ContainerAllocator>
00098 struct DataType< ::pr2_object_manipulation_msgs::GetGripperPoseGoal_<ContainerAllocator> > {
00099   static const char* value() 
00100   {
00101     return "pr2_object_manipulation_msgs/GetGripperPoseGoal";
00102   }
00103 
00104   static const char* value(const  ::pr2_object_manipulation_msgs::GetGripperPoseGoal_<ContainerAllocator> &) { return value(); } 
00105 };
00106 
00107 template<class ContainerAllocator>
00108 struct Definition< ::pr2_object_manipulation_msgs::GetGripperPoseGoal_<ContainerAllocator> > {
00109   static const char* value() 
00110   {
00111     return "# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00112 \n\
00113 # for which arm are we requesting a pose\n\
00114 # useful for knowing which arm to initialize from when seed is empty\n\
00115 string arm_name\n\
00116 \n\
00117 # a seed position for the ghosted gripper. If emtpy (quaternion of norm 0)\n\
00118 # the ghosted gripper will be initialized at the current position of the gripper\n\
00119 geometry_msgs/PoseStamped gripper_pose\n\
00120 float32 gripper_opening\n\
00121 \n\
00122 # An object that the gripper is holding. May be empty.\n\
00123 object_manipulation_msgs/GraspableObject object\n\
00124 \n\
00125 # how we are holding the object, if any.\n\
00126 object_manipulation_msgs/Grasp grasp\n\
00127 \n\
00128 \n\
00129 ================================================================================\n\
00130 MSG: geometry_msgs/PoseStamped\n\
00131 # A Pose with reference coordinate frame and timestamp\n\
00132 Header header\n\
00133 Pose pose\n\
00134 \n\
00135 ================================================================================\n\
00136 MSG: std_msgs/Header\n\
00137 # Standard metadata for higher-level stamped data types.\n\
00138 # This is generally used to communicate timestamped data \n\
00139 # in a particular coordinate frame.\n\
00140 # \n\
00141 # sequence ID: consecutively increasing ID \n\
00142 uint32 seq\n\
00143 #Two-integer timestamp that is expressed as:\n\
00144 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00145 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00146 # time-handling sugar is provided by the client library\n\
00147 time stamp\n\
00148 #Frame this data is associated with\n\
00149 # 0: no frame\n\
00150 # 1: global frame\n\
00151 string frame_id\n\
00152 \n\
00153 ================================================================================\n\
00154 MSG: geometry_msgs/Pose\n\
00155 # A representation of pose in free space, composed of postion and orientation. \n\
00156 Point position\n\
00157 Quaternion orientation\n\
00158 \n\
00159 ================================================================================\n\
00160 MSG: geometry_msgs/Point\n\
00161 # This contains the position of a point in free space\n\
00162 float64 x\n\
00163 float64 y\n\
00164 float64 z\n\
00165 \n\
00166 ================================================================================\n\
00167 MSG: geometry_msgs/Quaternion\n\
00168 # This represents an orientation in free space in quaternion form.\n\
00169 \n\
00170 float64 x\n\
00171 float64 y\n\
00172 float64 z\n\
00173 float64 w\n\
00174 \n\
00175 ================================================================================\n\
00176 MSG: object_manipulation_msgs/GraspableObject\n\
00177 # an object that the object_manipulator can work on\n\
00178 \n\
00179 # a graspable object can be represented in multiple ways. This message\n\
00180 # can contain all of them. Which one is actually used is up to the receiver\n\
00181 # of this message. When adding new representations, one must be careful that\n\
00182 # they have reasonable lightweight defaults indicating that that particular\n\
00183 # representation is not available.\n\
00184 \n\
00185 # the tf frame to be used as a reference frame when combining information from\n\
00186 # the different representations below\n\
00187 string reference_frame_id\n\
00188 \n\
00189 # potential recognition results from a database of models\n\
00190 # all poses are relative to the object reference pose\n\
00191 household_objects_database_msgs/DatabaseModelPose[] potential_models\n\
00192 \n\
00193 # the point cloud itself\n\
00194 sensor_msgs/PointCloud cluster\n\
00195 \n\
00196 # a region of a PointCloud2 of interest\n\
00197 object_manipulation_msgs/SceneRegion region\n\
00198 \n\
00199 # the name that this object has in the collision environment\n\
00200 string collision_name\n\
00201 ================================================================================\n\
00202 MSG: household_objects_database_msgs/DatabaseModelPose\n\
00203 # Informs that a specific model from the Model Database has been \n\
00204 # identified at a certain location\n\
00205 \n\
00206 # the database id of the model\n\
00207 int32 model_id\n\
00208 \n\
00209 # the pose that it can be found in\n\
00210 geometry_msgs/PoseStamped pose\n\
00211 \n\
00212 # a measure of the confidence level in this detection result\n\
00213 float32 confidence\n\
00214 \n\
00215 # the name of the object detector that generated this detection result\n\
00216 string detector_name\n\
00217 \n\
00218 ================================================================================\n\
00219 MSG: sensor_msgs/PointCloud\n\
00220 # This message holds a collection of 3d points, plus optional additional\n\
00221 # information about each point.\n\
00222 \n\
00223 # Time of sensor data acquisition, coordinate frame ID.\n\
00224 Header header\n\
00225 \n\
00226 # Array of 3d points. Each Point32 should be interpreted as a 3d point\n\
00227 # in the frame given in the header.\n\
00228 geometry_msgs/Point32[] points\n\
00229 \n\
00230 # Each channel should have the same number of elements as points array,\n\
00231 # and the data in each channel should correspond 1:1 with each point.\n\
00232 # Channel names in common practice are listed in ChannelFloat32.msg.\n\
00233 ChannelFloat32[] channels\n\
00234 \n\
00235 ================================================================================\n\
00236 MSG: geometry_msgs/Point32\n\
00237 # This contains the position of a point in free space(with 32 bits of precision).\n\
00238 # It is recommeded to use Point wherever possible instead of Point32.  \n\
00239 # \n\
00240 # This recommendation is to promote interoperability.  \n\
00241 #\n\
00242 # This message is designed to take up less space when sending\n\
00243 # lots of points at once, as in the case of a PointCloud.  \n\
00244 \n\
00245 float32 x\n\
00246 float32 y\n\
00247 float32 z\n\
00248 ================================================================================\n\
00249 MSG: sensor_msgs/ChannelFloat32\n\
00250 # This message is used by the PointCloud message to hold optional data\n\
00251 # associated with each point in the cloud. The length of the values\n\
00252 # array should be the same as the length of the points array in the\n\
00253 # PointCloud, and each value should be associated with the corresponding\n\
00254 # point.\n\
00255 \n\
00256 # Channel names in existing practice include:\n\
00257 #   \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\
00258 #              This is opposite to usual conventions but remains for\n\
00259 #              historical reasons. The newer PointCloud2 message has no\n\
00260 #              such problem.\n\
00261 #   \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\
00262 #           (R,G,B) values packed into the least significant 24 bits,\n\
00263 #           in order.\n\
00264 #   \"intensity\" - laser or pixel intensity.\n\
00265 #   \"distance\"\n\
00266 \n\
00267 # The channel name should give semantics of the channel (e.g.\n\
00268 # \"intensity\" instead of \"value\").\n\
00269 string name\n\
00270 \n\
00271 # The values array should be 1-1 with the elements of the associated\n\
00272 # PointCloud.\n\
00273 float32[] values\n\
00274 \n\
00275 ================================================================================\n\
00276 MSG: object_manipulation_msgs/SceneRegion\n\
00277 # Point cloud\n\
00278 sensor_msgs/PointCloud2 cloud\n\
00279 \n\
00280 # Indices for the region of interest\n\
00281 int32[] mask\n\
00282 \n\
00283 # One of the corresponding 2D images, if applicable\n\
00284 sensor_msgs/Image image\n\
00285 \n\
00286 # The disparity image, if applicable\n\
00287 sensor_msgs/Image disparity_image\n\
00288 \n\
00289 # Camera info for the camera that took the image\n\
00290 sensor_msgs/CameraInfo cam_info\n\
00291 \n\
00292 # a 3D region of interest for grasp planning\n\
00293 geometry_msgs/PoseStamped  roi_box_pose\n\
00294 geometry_msgs/Vector3      roi_box_dims\n\
00295 \n\
00296 ================================================================================\n\
00297 MSG: sensor_msgs/PointCloud2\n\
00298 # This message holds a collection of N-dimensional points, which may\n\
00299 # contain additional information such as normals, intensity, etc. The\n\
00300 # point data is stored as a binary blob, its layout described by the\n\
00301 # contents of the \"fields\" array.\n\
00302 \n\
00303 # The point cloud data may be organized 2d (image-like) or 1d\n\
00304 # (unordered). Point clouds organized as 2d images may be produced by\n\
00305 # camera depth sensors such as stereo or time-of-flight.\n\
00306 \n\
00307 # Time of sensor data acquisition, and the coordinate frame ID (for 3d\n\
00308 # points).\n\
00309 Header header\n\
00310 \n\
00311 # 2D structure of the point cloud. If the cloud is unordered, height is\n\
00312 # 1 and width is the length of the point cloud.\n\
00313 uint32 height\n\
00314 uint32 width\n\
00315 \n\
00316 # Describes the channels and their layout in the binary data blob.\n\
00317 PointField[] fields\n\
00318 \n\
00319 bool    is_bigendian # Is this data bigendian?\n\
00320 uint32  point_step   # Length of a point in bytes\n\
00321 uint32  row_step     # Length of a row in bytes\n\
00322 uint8[] data         # Actual point data, size is (row_step*height)\n\
00323 \n\
00324 bool is_dense        # True if there are no invalid points\n\
00325 \n\
00326 ================================================================================\n\
00327 MSG: sensor_msgs/PointField\n\
00328 # This message holds the description of one point entry in the\n\
00329 # PointCloud2 message format.\n\
00330 uint8 INT8    = 1\n\
00331 uint8 UINT8   = 2\n\
00332 uint8 INT16   = 3\n\
00333 uint8 UINT16  = 4\n\
00334 uint8 INT32   = 5\n\
00335 uint8 UINT32  = 6\n\
00336 uint8 FLOAT32 = 7\n\
00337 uint8 FLOAT64 = 8\n\
00338 \n\
00339 string name      # Name of field\n\
00340 uint32 offset    # Offset from start of point struct\n\
00341 uint8  datatype  # Datatype enumeration, see above\n\
00342 uint32 count     # How many elements in the field\n\
00343 \n\
00344 ================================================================================\n\
00345 MSG: sensor_msgs/Image\n\
00346 # This message contains an uncompressed image\n\
00347 # (0, 0) is at top-left corner of image\n\
00348 #\n\
00349 \n\
00350 Header header        # Header timestamp should be acquisition time of image\n\
00351                      # Header frame_id should be optical frame of camera\n\
00352                      # origin of frame should be optical center of cameara\n\
00353                      # +x should point to the right in the image\n\
00354                      # +y should point down in the image\n\
00355                      # +z should point into to plane of the image\n\
00356                      # If the frame_id here and the frame_id of the CameraInfo\n\
00357                      # message associated with the image conflict\n\
00358                      # the behavior is undefined\n\
00359 \n\
00360 uint32 height         # image height, that is, number of rows\n\
00361 uint32 width          # image width, that is, number of columns\n\
00362 \n\
00363 # The legal values for encoding are in file src/image_encodings.cpp\n\
00364 # If you want to standardize a new string format, join\n\
00365 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.\n\
00366 \n\
00367 string encoding       # Encoding of pixels -- channel meaning, ordering, size\n\
00368                       # taken from the list of strings in src/image_encodings.cpp\n\
00369 \n\
00370 uint8 is_bigendian    # is this data bigendian?\n\
00371 uint32 step           # Full row length in bytes\n\
00372 uint8[] data          # actual matrix data, size is (step * rows)\n\
00373 \n\
00374 ================================================================================\n\
00375 MSG: sensor_msgs/CameraInfo\n\
00376 # This message defines meta information for a camera. It should be in a\n\
00377 # camera namespace on topic \"camera_info\" and accompanied by up to five\n\
00378 # image topics named:\n\
00379 #\n\
00380 #   image_raw - raw data from the camera driver, possibly Bayer encoded\n\
00381 #   image            - monochrome, distorted\n\
00382 #   image_color      - color, distorted\n\
00383 #   image_rect       - monochrome, rectified\n\
00384 #   image_rect_color - color, rectified\n\
00385 #\n\
00386 # The image_pipeline contains packages (image_proc, stereo_image_proc)\n\
00387 # for producing the four processed image topics from image_raw and\n\
00388 # camera_info. The meaning of the camera parameters are described in\n\
00389 # detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.\n\
00390 #\n\
00391 # The image_geometry package provides a user-friendly interface to\n\
00392 # common operations using this meta information. If you want to, e.g.,\n\
00393 # project a 3d point into image coordinates, we strongly recommend\n\
00394 # using image_geometry.\n\
00395 #\n\
00396 # If the camera is uncalibrated, the matrices D, K, R, P should be left\n\
00397 # zeroed out. In particular, clients may assume that K[0] == 0.0\n\
00398 # indicates an uncalibrated camera.\n\
00399 \n\
00400 #######################################################################\n\
00401 #                     Image acquisition info                          #\n\
00402 #######################################################################\n\
00403 \n\
00404 # Time of image acquisition, camera coordinate frame ID\n\
00405 Header header    # Header timestamp should be acquisition time of image\n\
00406                  # Header frame_id should be optical frame of camera\n\
00407                  # origin of frame should be optical center of camera\n\
00408                  # +x should point to the right in the image\n\
00409                  # +y should point down in the image\n\
00410                  # +z should point into the plane of the image\n\
00411 \n\
00412 \n\
00413 #######################################################################\n\
00414 #                      Calibration Parameters                         #\n\
00415 #######################################################################\n\
00416 # These are fixed during camera calibration. Their values will be the #\n\
00417 # same in all messages until the camera is recalibrated. Note that    #\n\
00418 # self-calibrating systems may \"recalibrate\" frequently.              #\n\
00419 #                                                                     #\n\
00420 # The internal parameters can be used to warp a raw (distorted) image #\n\
00421 # to:                                                                 #\n\
00422 #   1. An undistorted image (requires D and K)                        #\n\
00423 #   2. A rectified image (requires D, K, R)                           #\n\
00424 # The projection matrix P projects 3D points into the rectified image.#\n\
00425 #######################################################################\n\
00426 \n\
00427 # The image dimensions with which the camera was calibrated. Normally\n\
00428 # this will be the full camera resolution in pixels.\n\
00429 uint32 height\n\
00430 uint32 width\n\
00431 \n\
00432 # The distortion model used. Supported models are listed in\n\
00433 # sensor_msgs/distortion_models.h. For most cameras, \"plumb_bob\" - a\n\
00434 # simple model of radial and tangential distortion - is sufficent.\n\
00435 string distortion_model\n\
00436 \n\
00437 # The distortion parameters, size depending on the distortion model.\n\
00438 # For \"plumb_bob\", the 5 parameters are: (k1, k2, t1, t2, k3).\n\
00439 float64[] D\n\
00440 \n\
00441 # Intrinsic camera matrix for the raw (distorted) images.\n\
00442 #     [fx  0 cx]\n\
00443 # K = [ 0 fy cy]\n\
00444 #     [ 0  0  1]\n\
00445 # Projects 3D points in the camera coordinate frame to 2D pixel\n\
00446 # coordinates using the focal lengths (fx, fy) and principal point\n\
00447 # (cx, cy).\n\
00448 float64[9]  K # 3x3 row-major matrix\n\
00449 \n\
00450 # Rectification matrix (stereo cameras only)\n\
00451 # A rotation matrix aligning the camera coordinate system to the ideal\n\
00452 # stereo image plane so that epipolar lines in both stereo images are\n\
00453 # parallel.\n\
00454 float64[9]  R # 3x3 row-major matrix\n\
00455 \n\
00456 # Projection/camera matrix\n\
00457 #     [fx'  0  cx' Tx]\n\
00458 # P = [ 0  fy' cy' Ty]\n\
00459 #     [ 0   0   1   0]\n\
00460 # By convention, this matrix specifies the intrinsic (camera) matrix\n\
00461 #  of the processed (rectified) image. That is, the left 3x3 portion\n\
00462 #  is the normal camera intrinsic matrix for the rectified image.\n\
00463 # It projects 3D points in the camera coordinate frame to 2D pixel\n\
00464 #  coordinates using the focal lengths (fx', fy') and principal point\n\
00465 #  (cx', cy') - these may differ from the values in K.\n\
00466 # For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will\n\
00467 #  also have R = the identity and P[1:3,1:3] = K.\n\
00468 # For a stereo pair, the fourth column [Tx Ty 0]' is related to the\n\
00469 #  position of the optical center of the second camera in the first\n\
00470 #  camera's frame. We assume Tz = 0 so both cameras are in the same\n\
00471 #  stereo image plane. The first camera always has Tx = Ty = 0. For\n\
00472 #  the right (second) camera of a horizontal stereo pair, Ty = 0 and\n\
00473 #  Tx = -fx' * B, where B is the baseline between the cameras.\n\
00474 # Given a 3D point [X Y Z]', the projection (x, y) of the point onto\n\
00475 #  the rectified image is given by:\n\
00476 #  [u v w]' = P * [X Y Z 1]'\n\
00477 #         x = u / w\n\
00478 #         y = v / w\n\
00479 #  This holds for both images of a stereo pair.\n\
00480 float64[12] P # 3x4 row-major matrix\n\
00481 \n\
00482 \n\
00483 #######################################################################\n\
00484 #                      Operational Parameters                         #\n\
00485 #######################################################################\n\
00486 # These define the image region actually captured by the camera       #\n\
00487 # driver. Although they affect the geometry of the output image, they #\n\
00488 # may be changed freely without recalibrating the camera.             #\n\
00489 #######################################################################\n\
00490 \n\
00491 # Binning refers here to any camera setting which combines rectangular\n\
00492 #  neighborhoods of pixels into larger \"super-pixels.\" It reduces the\n\
00493 #  resolution of the output image to\n\
00494 #  (width / binning_x) x (height / binning_y).\n\
00495 # The default values binning_x = binning_y = 0 is considered the same\n\
00496 #  as binning_x = binning_y = 1 (no subsampling).\n\
00497 uint32 binning_x\n\
00498 uint32 binning_y\n\
00499 \n\
00500 # Region of interest (subwindow of full camera resolution), given in\n\
00501 #  full resolution (unbinned) image coordinates. A particular ROI\n\
00502 #  always denotes the same window of pixels on the camera sensor,\n\
00503 #  regardless of binning settings.\n\
00504 # The default setting of roi (all values 0) is considered the same as\n\
00505 #  full resolution (roi.width = width, roi.height = height).\n\
00506 RegionOfInterest roi\n\
00507 \n\
00508 ================================================================================\n\
00509 MSG: sensor_msgs/RegionOfInterest\n\
00510 # This message is used to specify a region of interest within an image.\n\
00511 #\n\
00512 # When used to specify the ROI setting of the camera when the image was\n\
00513 # taken, the height and width fields should either match the height and\n\
00514 # width fields for the associated image; or height = width = 0\n\
00515 # indicates that the full resolution image was captured.\n\
00516 \n\
00517 uint32 x_offset  # Leftmost pixel of the ROI\n\
00518                  # (0 if the ROI includes the left edge of the image)\n\
00519 uint32 y_offset  # Topmost pixel of the ROI\n\
00520                  # (0 if the ROI includes the top edge of the image)\n\
00521 uint32 height    # Height of ROI\n\
00522 uint32 width     # Width of ROI\n\
00523 \n\
00524 # True if a distinct rectified ROI should be calculated from the \"raw\"\n\
00525 # ROI in this message. Typically this should be False if the full image\n\
00526 # is captured (ROI not used), and True if a subwindow is captured (ROI\n\
00527 # used).\n\
00528 bool do_rectify\n\
00529 \n\
00530 ================================================================================\n\
00531 MSG: geometry_msgs/Vector3\n\
00532 # This represents a vector in free space. \n\
00533 \n\
00534 float64 x\n\
00535 float64 y\n\
00536 float64 z\n\
00537 ================================================================================\n\
00538 MSG: object_manipulation_msgs/Grasp\n\
00539 \n\
00540 # The internal posture of the hand for the pre-grasp\n\
00541 # only positions are used\n\
00542 sensor_msgs/JointState pre_grasp_posture\n\
00543 \n\
00544 # The internal posture of the hand for the grasp\n\
00545 # positions and efforts are used\n\
00546 sensor_msgs/JointState grasp_posture\n\
00547 \n\
00548 # The position of the end-effector for the grasp relative to a reference frame \n\
00549 # (that is always specified elsewhere, not in this message)\n\
00550 geometry_msgs/Pose grasp_pose\n\
00551 \n\
00552 # The estimated probability of success for this grasp\n\
00553 float64 success_probability\n\
00554 \n\
00555 # Debug flag to indicate that this grasp would be the best in its cluster\n\
00556 bool cluster_rep\n\
00557 \n\
00558 # how far the pre-grasp should ideally be away from the grasp\n\
00559 float32 desired_approach_distance\n\
00560 \n\
00561 # how much distance between pre-grasp and grasp must actually be feasible \n\
00562 # for the grasp not to be rejected\n\
00563 float32 min_approach_distance\n\
00564 \n\
00565 # an optional list of obstacles that we have semantic information about\n\
00566 # and that we expect might move in the course of executing this grasp\n\
00567 # the grasp planner is expected to make sure they move in an OK way; during\n\
00568 # execution, grasp executors will not check for collisions against these objects\n\
00569 GraspableObject[] moved_obstacles\n\
00570 \n\
00571 ================================================================================\n\
00572 MSG: sensor_msgs/JointState\n\
00573 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\
00574 #\n\
00575 # The state of each joint (revolute or prismatic) is defined by:\n\
00576 #  * the position of the joint (rad or m),\n\
00577 #  * the velocity of the joint (rad/s or m/s) and \n\
00578 #  * the effort that is applied in the joint (Nm or N).\n\
00579 #\n\
00580 # Each joint is uniquely identified by its name\n\
00581 # The header specifies the time at which the joint states were recorded. All the joint states\n\
00582 # in one message have to be recorded at the same time.\n\
00583 #\n\
00584 # This message consists of a multiple arrays, one for each part of the joint state. \n\
00585 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
00586 # effort associated with them, you can leave the effort array empty. \n\
00587 #\n\
00588 # All arrays in this message should have the same size, or be empty.\n\
00589 # This is the only way to uniquely associate the joint name with the correct\n\
00590 # states.\n\
00591 \n\
00592 \n\
00593 Header header\n\
00594 \n\
00595 string[] name\n\
00596 float64[] position\n\
00597 float64[] velocity\n\
00598 float64[] effort\n\
00599 \n\
00600 ";
00601   }
00602 
00603   static const char* value(const  ::pr2_object_manipulation_msgs::GetGripperPoseGoal_<ContainerAllocator> &) { return value(); } 
00604 };
00605 
00606 } // namespace message_traits
00607 } // namespace ros
00608 
00609 namespace ros
00610 {
00611 namespace serialization
00612 {
00613 
00614 template<class ContainerAllocator> struct Serializer< ::pr2_object_manipulation_msgs::GetGripperPoseGoal_<ContainerAllocator> >
00615 {
00616   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00617   {
00618     stream.next(m.arm_name);
00619     stream.next(m.gripper_pose);
00620     stream.next(m.gripper_opening);
00621     stream.next(m.object);
00622     stream.next(m.grasp);
00623   }
00624 
00625   ROS_DECLARE_ALLINONE_SERIALIZER;
00626 }; // struct GetGripperPoseGoal_
00627 } // namespace serialization
00628 } // namespace ros
00629 
00630 namespace ros
00631 {
00632 namespace message_operations
00633 {
00634 
00635 template<class ContainerAllocator>
00636 struct Printer< ::pr2_object_manipulation_msgs::GetGripperPoseGoal_<ContainerAllocator> >
00637 {
00638   template<typename Stream> static void stream(Stream& s, const std::string& indent, const  ::pr2_object_manipulation_msgs::GetGripperPoseGoal_<ContainerAllocator> & v) 
00639   {
00640     s << indent << "arm_name: ";
00641     Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + "  ", v.arm_name);
00642     s << indent << "gripper_pose: ";
00643 s << std::endl;
00644     Printer< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::stream(s, indent + "  ", v.gripper_pose);
00645     s << indent << "gripper_opening: ";
00646     Printer<float>::stream(s, indent + "  ", v.gripper_opening);
00647     s << indent << "object: ";
00648 s << std::endl;
00649     Printer< ::object_manipulation_msgs::GraspableObject_<ContainerAllocator> >::stream(s, indent + "  ", v.object);
00650     s << indent << "grasp: ";
00651 s << std::endl;
00652     Printer< ::object_manipulation_msgs::Grasp_<ContainerAllocator> >::stream(s, indent + "  ", v.grasp);
00653   }
00654 };
00655 
00656 
00657 } // namespace message_operations
00658 } // namespace ros
00659 
00660 #endif // PR2_OBJECT_MANIPULATION_MSGS_MESSAGE_GETGRIPPERPOSEGOAL_H
00661 


pr2_object_manipulation_msgs
Author(s): Matei Ciocarlie
autogenerated on Fri Jan 3 2014 11:59:13