$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-pr2_object_manipulation/doc_stacks/2013-03-05_12-10-38.333207/pr2_object_manipulation/manipulation/pr2_grasp_adjust/msg/GraspAdjustGoal.msg */ 00002 #ifndef PR2_GRASP_ADJUST_MESSAGE_GRASPADJUSTGOAL_H 00003 #define PR2_GRASP_ADJUST_MESSAGE_GRASPADJUSTGOAL_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 "sensor_msgs/PointCloud2.h" 00018 #include "geometry_msgs/PoseStamped.h" 00019 00020 namespace pr2_grasp_adjust 00021 { 00022 template <class ContainerAllocator> 00023 struct GraspAdjustGoal_ { 00024 typedef GraspAdjustGoal_<ContainerAllocator> Type; 00025 00026 GraspAdjustGoal_() 00027 : cloud() 00028 , pose_stamped() 00029 , use_orientation(false) 00030 , seed_index(0) 00031 , search_mode(0) 00032 { 00033 } 00034 00035 GraspAdjustGoal_(const ContainerAllocator& _alloc) 00036 : cloud(_alloc) 00037 , pose_stamped(_alloc) 00038 , use_orientation(false) 00039 , seed_index(0) 00040 , search_mode(0) 00041 { 00042 } 00043 00044 typedef ::sensor_msgs::PointCloud2_<ContainerAllocator> _cloud_type; 00045 ::sensor_msgs::PointCloud2_<ContainerAllocator> cloud; 00046 00047 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _pose_stamped_type; 00048 ::geometry_msgs::PoseStamped_<ContainerAllocator> pose_stamped; 00049 00050 typedef uint8_t _use_orientation_type; 00051 uint8_t use_orientation; 00052 00053 typedef int32_t _seed_index_type; 00054 int32_t seed_index; 00055 00056 typedef uint8_t _search_mode_type; 00057 uint8_t search_mode; 00058 00059 enum { GLOBAL_SEARCH = 0 }; 00060 enum { LOCAL_SEARCH = 1 }; 00061 enum { SINGLE_POSE = 2 }; 00062 00063 private: 00064 static const char* __s_getDataType_() { return "pr2_grasp_adjust/GraspAdjustGoal"; } 00065 public: 00066 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00067 00068 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00069 00070 private: 00071 static const char* __s_getMD5Sum_() { return "060fcd54eb8073631ee72fceac5fcf37"; } 00072 public: 00073 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00074 00075 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00076 00077 private: 00078 static const char* __s_getMessageDefinition_() { return "# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\ 00079 #goal definition\n\ 00080 \n\ 00081 sensor_msgs/PointCloud2 cloud\n\ 00082 geometry_msgs/PoseStamped pose_stamped\n\ 00083 bool use_orientation\n\ 00084 int32 seed_index\n\ 00085 uint8 search_mode\n\ 00086 \n\ 00087 int32 GLOBAL_SEARCH = 0\n\ 00088 int32 LOCAL_SEARCH = 1\n\ 00089 int32 SINGLE_POSE = 2\n\ 00090 \n\ 00091 \n\ 00092 ================================================================================\n\ 00093 MSG: sensor_msgs/PointCloud2\n\ 00094 # This message holds a collection of N-dimensional points, which may\n\ 00095 # contain additional information such as normals, intensity, etc. The\n\ 00096 # point data is stored as a binary blob, its layout described by the\n\ 00097 # contents of the \"fields\" array.\n\ 00098 \n\ 00099 # The point cloud data may be organized 2d (image-like) or 1d\n\ 00100 # (unordered). Point clouds organized as 2d images may be produced by\n\ 00101 # camera depth sensors such as stereo or time-of-flight.\n\ 00102 \n\ 00103 # Time of sensor data acquisition, and the coordinate frame ID (for 3d\n\ 00104 # points).\n\ 00105 Header header\n\ 00106 \n\ 00107 # 2D structure of the point cloud. If the cloud is unordered, height is\n\ 00108 # 1 and width is the length of the point cloud.\n\ 00109 uint32 height\n\ 00110 uint32 width\n\ 00111 \n\ 00112 # Describes the channels and their layout in the binary data blob.\n\ 00113 PointField[] fields\n\ 00114 \n\ 00115 bool is_bigendian # Is this data bigendian?\n\ 00116 uint32 point_step # Length of a point in bytes\n\ 00117 uint32 row_step # Length of a row in bytes\n\ 00118 uint8[] data # Actual point data, size is (row_step*height)\n\ 00119 \n\ 00120 bool is_dense # True if there are no invalid points\n\ 00121 \n\ 00122 ================================================================================\n\ 00123 MSG: std_msgs/Header\n\ 00124 # Standard metadata for higher-level stamped data types.\n\ 00125 # This is generally used to communicate timestamped data \n\ 00126 # in a particular coordinate frame.\n\ 00127 # \n\ 00128 # sequence ID: consecutively increasing ID \n\ 00129 uint32 seq\n\ 00130 #Two-integer timestamp that is expressed as:\n\ 00131 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00132 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00133 # time-handling sugar is provided by the client library\n\ 00134 time stamp\n\ 00135 #Frame this data is associated with\n\ 00136 # 0: no frame\n\ 00137 # 1: global frame\n\ 00138 string frame_id\n\ 00139 \n\ 00140 ================================================================================\n\ 00141 MSG: sensor_msgs/PointField\n\ 00142 # This message holds the description of one point entry in the\n\ 00143 # PointCloud2 message format.\n\ 00144 uint8 INT8 = 1\n\ 00145 uint8 UINT8 = 2\n\ 00146 uint8 INT16 = 3\n\ 00147 uint8 UINT16 = 4\n\ 00148 uint8 INT32 = 5\n\ 00149 uint8 UINT32 = 6\n\ 00150 uint8 FLOAT32 = 7\n\ 00151 uint8 FLOAT64 = 8\n\ 00152 \n\ 00153 string name # Name of field\n\ 00154 uint32 offset # Offset from start of point struct\n\ 00155 uint8 datatype # Datatype enumeration, see above\n\ 00156 uint32 count # How many elements in the field\n\ 00157 \n\ 00158 ================================================================================\n\ 00159 MSG: geometry_msgs/PoseStamped\n\ 00160 # A Pose with reference coordinate frame and timestamp\n\ 00161 Header header\n\ 00162 Pose pose\n\ 00163 \n\ 00164 ================================================================================\n\ 00165 MSG: geometry_msgs/Pose\n\ 00166 # A representation of pose in free space, composed of postion and orientation. \n\ 00167 Point position\n\ 00168 Quaternion orientation\n\ 00169 \n\ 00170 ================================================================================\n\ 00171 MSG: geometry_msgs/Point\n\ 00172 # This contains the position of a point in free space\n\ 00173 float64 x\n\ 00174 float64 y\n\ 00175 float64 z\n\ 00176 \n\ 00177 ================================================================================\n\ 00178 MSG: geometry_msgs/Quaternion\n\ 00179 # This represents an orientation in free space in quaternion form.\n\ 00180 \n\ 00181 float64 x\n\ 00182 float64 y\n\ 00183 float64 z\n\ 00184 float64 w\n\ 00185 \n\ 00186 "; } 00187 public: 00188 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00189 00190 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00191 00192 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00193 { 00194 ros::serialization::OStream stream(write_ptr, 1000000000); 00195 ros::serialization::serialize(stream, cloud); 00196 ros::serialization::serialize(stream, pose_stamped); 00197 ros::serialization::serialize(stream, use_orientation); 00198 ros::serialization::serialize(stream, seed_index); 00199 ros::serialization::serialize(stream, search_mode); 00200 return stream.getData(); 00201 } 00202 00203 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00204 { 00205 ros::serialization::IStream stream(read_ptr, 1000000000); 00206 ros::serialization::deserialize(stream, cloud); 00207 ros::serialization::deserialize(stream, pose_stamped); 00208 ros::serialization::deserialize(stream, use_orientation); 00209 ros::serialization::deserialize(stream, seed_index); 00210 ros::serialization::deserialize(stream, search_mode); 00211 return stream.getData(); 00212 } 00213 00214 ROS_DEPRECATED virtual uint32_t serializationLength() const 00215 { 00216 uint32_t size = 0; 00217 size += ros::serialization::serializationLength(cloud); 00218 size += ros::serialization::serializationLength(pose_stamped); 00219 size += ros::serialization::serializationLength(use_orientation); 00220 size += ros::serialization::serializationLength(seed_index); 00221 size += ros::serialization::serializationLength(search_mode); 00222 return size; 00223 } 00224 00225 typedef boost::shared_ptr< ::pr2_grasp_adjust::GraspAdjustGoal_<ContainerAllocator> > Ptr; 00226 typedef boost::shared_ptr< ::pr2_grasp_adjust::GraspAdjustGoal_<ContainerAllocator> const> ConstPtr; 00227 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00228 }; // struct GraspAdjustGoal 00229 typedef ::pr2_grasp_adjust::GraspAdjustGoal_<std::allocator<void> > GraspAdjustGoal; 00230 00231 typedef boost::shared_ptr< ::pr2_grasp_adjust::GraspAdjustGoal> GraspAdjustGoalPtr; 00232 typedef boost::shared_ptr< ::pr2_grasp_adjust::GraspAdjustGoal const> GraspAdjustGoalConstPtr; 00233 00234 00235 template<typename ContainerAllocator> 00236 std::ostream& operator<<(std::ostream& s, const ::pr2_grasp_adjust::GraspAdjustGoal_<ContainerAllocator> & v) 00237 { 00238 ros::message_operations::Printer< ::pr2_grasp_adjust::GraspAdjustGoal_<ContainerAllocator> >::stream(s, "", v); 00239 return s;} 00240 00241 } // namespace pr2_grasp_adjust 00242 00243 namespace ros 00244 { 00245 namespace message_traits 00246 { 00247 template<class ContainerAllocator> struct IsMessage< ::pr2_grasp_adjust::GraspAdjustGoal_<ContainerAllocator> > : public TrueType {}; 00248 template<class ContainerAllocator> struct IsMessage< ::pr2_grasp_adjust::GraspAdjustGoal_<ContainerAllocator> const> : public TrueType {}; 00249 template<class ContainerAllocator> 00250 struct MD5Sum< ::pr2_grasp_adjust::GraspAdjustGoal_<ContainerAllocator> > { 00251 static const char* value() 00252 { 00253 return "060fcd54eb8073631ee72fceac5fcf37"; 00254 } 00255 00256 static const char* value(const ::pr2_grasp_adjust::GraspAdjustGoal_<ContainerAllocator> &) { return value(); } 00257 static const uint64_t static_value1 = 0x060fcd54eb807363ULL; 00258 static const uint64_t static_value2 = 0x1ee72fceac5fcf37ULL; 00259 }; 00260 00261 template<class ContainerAllocator> 00262 struct DataType< ::pr2_grasp_adjust::GraspAdjustGoal_<ContainerAllocator> > { 00263 static const char* value() 00264 { 00265 return "pr2_grasp_adjust/GraspAdjustGoal"; 00266 } 00267 00268 static const char* value(const ::pr2_grasp_adjust::GraspAdjustGoal_<ContainerAllocator> &) { return value(); } 00269 }; 00270 00271 template<class ContainerAllocator> 00272 struct Definition< ::pr2_grasp_adjust::GraspAdjustGoal_<ContainerAllocator> > { 00273 static const char* value() 00274 { 00275 return "# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\ 00276 #goal definition\n\ 00277 \n\ 00278 sensor_msgs/PointCloud2 cloud\n\ 00279 geometry_msgs/PoseStamped pose_stamped\n\ 00280 bool use_orientation\n\ 00281 int32 seed_index\n\ 00282 uint8 search_mode\n\ 00283 \n\ 00284 int32 GLOBAL_SEARCH = 0\n\ 00285 int32 LOCAL_SEARCH = 1\n\ 00286 int32 SINGLE_POSE = 2\n\ 00287 \n\ 00288 \n\ 00289 ================================================================================\n\ 00290 MSG: sensor_msgs/PointCloud2\n\ 00291 # This message holds a collection of N-dimensional points, which may\n\ 00292 # contain additional information such as normals, intensity, etc. The\n\ 00293 # point data is stored as a binary blob, its layout described by the\n\ 00294 # contents of the \"fields\" array.\n\ 00295 \n\ 00296 # The point cloud data may be organized 2d (image-like) or 1d\n\ 00297 # (unordered). Point clouds organized as 2d images may be produced by\n\ 00298 # camera depth sensors such as stereo or time-of-flight.\n\ 00299 \n\ 00300 # Time of sensor data acquisition, and the coordinate frame ID (for 3d\n\ 00301 # points).\n\ 00302 Header header\n\ 00303 \n\ 00304 # 2D structure of the point cloud. If the cloud is unordered, height is\n\ 00305 # 1 and width is the length of the point cloud.\n\ 00306 uint32 height\n\ 00307 uint32 width\n\ 00308 \n\ 00309 # Describes the channels and their layout in the binary data blob.\n\ 00310 PointField[] fields\n\ 00311 \n\ 00312 bool is_bigendian # Is this data bigendian?\n\ 00313 uint32 point_step # Length of a point in bytes\n\ 00314 uint32 row_step # Length of a row in bytes\n\ 00315 uint8[] data # Actual point data, size is (row_step*height)\n\ 00316 \n\ 00317 bool is_dense # True if there are no invalid points\n\ 00318 \n\ 00319 ================================================================================\n\ 00320 MSG: std_msgs/Header\n\ 00321 # Standard metadata for higher-level stamped data types.\n\ 00322 # This is generally used to communicate timestamped data \n\ 00323 # in a particular coordinate frame.\n\ 00324 # \n\ 00325 # sequence ID: consecutively increasing ID \n\ 00326 uint32 seq\n\ 00327 #Two-integer timestamp that is expressed as:\n\ 00328 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00329 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00330 # time-handling sugar is provided by the client library\n\ 00331 time stamp\n\ 00332 #Frame this data is associated with\n\ 00333 # 0: no frame\n\ 00334 # 1: global frame\n\ 00335 string frame_id\n\ 00336 \n\ 00337 ================================================================================\n\ 00338 MSG: sensor_msgs/PointField\n\ 00339 # This message holds the description of one point entry in the\n\ 00340 # PointCloud2 message format.\n\ 00341 uint8 INT8 = 1\n\ 00342 uint8 UINT8 = 2\n\ 00343 uint8 INT16 = 3\n\ 00344 uint8 UINT16 = 4\n\ 00345 uint8 INT32 = 5\n\ 00346 uint8 UINT32 = 6\n\ 00347 uint8 FLOAT32 = 7\n\ 00348 uint8 FLOAT64 = 8\n\ 00349 \n\ 00350 string name # Name of field\n\ 00351 uint32 offset # Offset from start of point struct\n\ 00352 uint8 datatype # Datatype enumeration, see above\n\ 00353 uint32 count # How many elements in the field\n\ 00354 \n\ 00355 ================================================================================\n\ 00356 MSG: geometry_msgs/PoseStamped\n\ 00357 # A Pose with reference coordinate frame and timestamp\n\ 00358 Header header\n\ 00359 Pose pose\n\ 00360 \n\ 00361 ================================================================================\n\ 00362 MSG: geometry_msgs/Pose\n\ 00363 # A representation of pose in free space, composed of postion and orientation. \n\ 00364 Point position\n\ 00365 Quaternion orientation\n\ 00366 \n\ 00367 ================================================================================\n\ 00368 MSG: geometry_msgs/Point\n\ 00369 # This contains the position of a point in free space\n\ 00370 float64 x\n\ 00371 float64 y\n\ 00372 float64 z\n\ 00373 \n\ 00374 ================================================================================\n\ 00375 MSG: geometry_msgs/Quaternion\n\ 00376 # This represents an orientation in free space in quaternion form.\n\ 00377 \n\ 00378 float64 x\n\ 00379 float64 y\n\ 00380 float64 z\n\ 00381 float64 w\n\ 00382 \n\ 00383 "; 00384 } 00385 00386 static const char* value(const ::pr2_grasp_adjust::GraspAdjustGoal_<ContainerAllocator> &) { return value(); } 00387 }; 00388 00389 } // namespace message_traits 00390 } // namespace ros 00391 00392 namespace ros 00393 { 00394 namespace serialization 00395 { 00396 00397 template<class ContainerAllocator> struct Serializer< ::pr2_grasp_adjust::GraspAdjustGoal_<ContainerAllocator> > 00398 { 00399 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00400 { 00401 stream.next(m.cloud); 00402 stream.next(m.pose_stamped); 00403 stream.next(m.use_orientation); 00404 stream.next(m.seed_index); 00405 stream.next(m.search_mode); 00406 } 00407 00408 ROS_DECLARE_ALLINONE_SERIALIZER; 00409 }; // struct GraspAdjustGoal_ 00410 } // namespace serialization 00411 } // namespace ros 00412 00413 namespace ros 00414 { 00415 namespace message_operations 00416 { 00417 00418 template<class ContainerAllocator> 00419 struct Printer< ::pr2_grasp_adjust::GraspAdjustGoal_<ContainerAllocator> > 00420 { 00421 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::pr2_grasp_adjust::GraspAdjustGoal_<ContainerAllocator> & v) 00422 { 00423 s << indent << "cloud: "; 00424 s << std::endl; 00425 Printer< ::sensor_msgs::PointCloud2_<ContainerAllocator> >::stream(s, indent + " ", v.cloud); 00426 s << indent << "pose_stamped: "; 00427 s << std::endl; 00428 Printer< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::stream(s, indent + " ", v.pose_stamped); 00429 s << indent << "use_orientation: "; 00430 Printer<uint8_t>::stream(s, indent + " ", v.use_orientation); 00431 s << indent << "seed_index: "; 00432 Printer<int32_t>::stream(s, indent + " ", v.seed_index); 00433 s << indent << "search_mode: "; 00434 Printer<uint8_t>::stream(s, indent + " ", v.search_mode); 00435 } 00436 }; 00437 00438 00439 } // namespace message_operations 00440 } // namespace ros 00441 00442 #endif // PR2_GRASP_ADJUST_MESSAGE_GRASPADJUSTGOAL_H 00443