$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-object_manipulation/doc_stacks/2013-03-01_16-13-18.345538/object_manipulation/object_manipulation_msgs/msg/ClusterBoundingBox.msg */ 00002 #ifndef OBJECT_MANIPULATION_MSGS_MESSAGE_CLUSTERBOUNDINGBOX_H 00003 #define OBJECT_MANIPULATION_MSGS_MESSAGE_CLUSTERBOUNDINGBOX_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 "geometry_msgs/Vector3.h" 00019 00020 namespace object_manipulation_msgs 00021 { 00022 template <class ContainerAllocator> 00023 struct ClusterBoundingBox_ { 00024 typedef ClusterBoundingBox_<ContainerAllocator> Type; 00025 00026 ClusterBoundingBox_() 00027 : pose_stamped() 00028 , dimensions() 00029 { 00030 } 00031 00032 ClusterBoundingBox_(const ContainerAllocator& _alloc) 00033 : pose_stamped(_alloc) 00034 , dimensions(_alloc) 00035 { 00036 } 00037 00038 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _pose_stamped_type; 00039 ::geometry_msgs::PoseStamped_<ContainerAllocator> pose_stamped; 00040 00041 typedef ::geometry_msgs::Vector3_<ContainerAllocator> _dimensions_type; 00042 ::geometry_msgs::Vector3_<ContainerAllocator> dimensions; 00043 00044 00045 private: 00046 static const char* __s_getDataType_() { return "object_manipulation_msgs/ClusterBoundingBox"; } 00047 public: 00048 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00049 00050 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00051 00052 private: 00053 static const char* __s_getMD5Sum_() { return "9bf2b7a44ad666dc3a6a2bbc21782dad"; } 00054 public: 00055 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00056 00057 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00058 00059 private: 00060 static const char* __s_getMessageDefinition_() { return "# contains a bounding box, which is essentially a box somewhere in space\n\ 00061 # used here ususally for the outlier-invariant bounding box of a cluster of points\n\ 00062 \n\ 00063 #the pose of the box frame\n\ 00064 geometry_msgs/PoseStamped pose_stamped\n\ 00065 \n\ 00066 #the dimensions of the box\n\ 00067 geometry_msgs/Vector3 dimensions\n\ 00068 \n\ 00069 ================================================================================\n\ 00070 MSG: geometry_msgs/PoseStamped\n\ 00071 # A Pose with reference coordinate frame and timestamp\n\ 00072 Header header\n\ 00073 Pose pose\n\ 00074 \n\ 00075 ================================================================================\n\ 00076 MSG: std_msgs/Header\n\ 00077 # Standard metadata for higher-level stamped data types.\n\ 00078 # This is generally used to communicate timestamped data \n\ 00079 # in a particular coordinate frame.\n\ 00080 # \n\ 00081 # sequence ID: consecutively increasing ID \n\ 00082 uint32 seq\n\ 00083 #Two-integer timestamp that is expressed as:\n\ 00084 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00085 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00086 # time-handling sugar is provided by the client library\n\ 00087 time stamp\n\ 00088 #Frame this data is associated with\n\ 00089 # 0: no frame\n\ 00090 # 1: global frame\n\ 00091 string frame_id\n\ 00092 \n\ 00093 ================================================================================\n\ 00094 MSG: geometry_msgs/Pose\n\ 00095 # A representation of pose in free space, composed of postion and orientation. \n\ 00096 Point position\n\ 00097 Quaternion orientation\n\ 00098 \n\ 00099 ================================================================================\n\ 00100 MSG: geometry_msgs/Point\n\ 00101 # This contains the position of a point in free space\n\ 00102 float64 x\n\ 00103 float64 y\n\ 00104 float64 z\n\ 00105 \n\ 00106 ================================================================================\n\ 00107 MSG: geometry_msgs/Quaternion\n\ 00108 # This represents an orientation in free space in quaternion form.\n\ 00109 \n\ 00110 float64 x\n\ 00111 float64 y\n\ 00112 float64 z\n\ 00113 float64 w\n\ 00114 \n\ 00115 ================================================================================\n\ 00116 MSG: geometry_msgs/Vector3\n\ 00117 # This represents a vector in free space. \n\ 00118 \n\ 00119 float64 x\n\ 00120 float64 y\n\ 00121 float64 z\n\ 00122 "; } 00123 public: 00124 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00125 00126 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00127 00128 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00129 { 00130 ros::serialization::OStream stream(write_ptr, 1000000000); 00131 ros::serialization::serialize(stream, pose_stamped); 00132 ros::serialization::serialize(stream, dimensions); 00133 return stream.getData(); 00134 } 00135 00136 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00137 { 00138 ros::serialization::IStream stream(read_ptr, 1000000000); 00139 ros::serialization::deserialize(stream, pose_stamped); 00140 ros::serialization::deserialize(stream, dimensions); 00141 return stream.getData(); 00142 } 00143 00144 ROS_DEPRECATED virtual uint32_t serializationLength() const 00145 { 00146 uint32_t size = 0; 00147 size += ros::serialization::serializationLength(pose_stamped); 00148 size += ros::serialization::serializationLength(dimensions); 00149 return size; 00150 } 00151 00152 typedef boost::shared_ptr< ::object_manipulation_msgs::ClusterBoundingBox_<ContainerAllocator> > Ptr; 00153 typedef boost::shared_ptr< ::object_manipulation_msgs::ClusterBoundingBox_<ContainerAllocator> const> ConstPtr; 00154 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00155 }; // struct ClusterBoundingBox 00156 typedef ::object_manipulation_msgs::ClusterBoundingBox_<std::allocator<void> > ClusterBoundingBox; 00157 00158 typedef boost::shared_ptr< ::object_manipulation_msgs::ClusterBoundingBox> ClusterBoundingBoxPtr; 00159 typedef boost::shared_ptr< ::object_manipulation_msgs::ClusterBoundingBox const> ClusterBoundingBoxConstPtr; 00160 00161 00162 template<typename ContainerAllocator> 00163 std::ostream& operator<<(std::ostream& s, const ::object_manipulation_msgs::ClusterBoundingBox_<ContainerAllocator> & v) 00164 { 00165 ros::message_operations::Printer< ::object_manipulation_msgs::ClusterBoundingBox_<ContainerAllocator> >::stream(s, "", v); 00166 return s;} 00167 00168 } // namespace object_manipulation_msgs 00169 00170 namespace ros 00171 { 00172 namespace message_traits 00173 { 00174 template<class ContainerAllocator> struct IsMessage< ::object_manipulation_msgs::ClusterBoundingBox_<ContainerAllocator> > : public TrueType {}; 00175 template<class ContainerAllocator> struct IsMessage< ::object_manipulation_msgs::ClusterBoundingBox_<ContainerAllocator> const> : public TrueType {}; 00176 template<class ContainerAllocator> 00177 struct MD5Sum< ::object_manipulation_msgs::ClusterBoundingBox_<ContainerAllocator> > { 00178 static const char* value() 00179 { 00180 return "9bf2b7a44ad666dc3a6a2bbc21782dad"; 00181 } 00182 00183 static const char* value(const ::object_manipulation_msgs::ClusterBoundingBox_<ContainerAllocator> &) { return value(); } 00184 static const uint64_t static_value1 = 0x9bf2b7a44ad666dcULL; 00185 static const uint64_t static_value2 = 0x3a6a2bbc21782dadULL; 00186 }; 00187 00188 template<class ContainerAllocator> 00189 struct DataType< ::object_manipulation_msgs::ClusterBoundingBox_<ContainerAllocator> > { 00190 static const char* value() 00191 { 00192 return "object_manipulation_msgs/ClusterBoundingBox"; 00193 } 00194 00195 static const char* value(const ::object_manipulation_msgs::ClusterBoundingBox_<ContainerAllocator> &) { return value(); } 00196 }; 00197 00198 template<class ContainerAllocator> 00199 struct Definition< ::object_manipulation_msgs::ClusterBoundingBox_<ContainerAllocator> > { 00200 static const char* value() 00201 { 00202 return "# contains a bounding box, which is essentially a box somewhere in space\n\ 00203 # used here ususally for the outlier-invariant bounding box of a cluster of points\n\ 00204 \n\ 00205 #the pose of the box frame\n\ 00206 geometry_msgs/PoseStamped pose_stamped\n\ 00207 \n\ 00208 #the dimensions of the box\n\ 00209 geometry_msgs/Vector3 dimensions\n\ 00210 \n\ 00211 ================================================================================\n\ 00212 MSG: geometry_msgs/PoseStamped\n\ 00213 # A Pose with reference coordinate frame and timestamp\n\ 00214 Header header\n\ 00215 Pose pose\n\ 00216 \n\ 00217 ================================================================================\n\ 00218 MSG: std_msgs/Header\n\ 00219 # Standard metadata for higher-level stamped data types.\n\ 00220 # This is generally used to communicate timestamped data \n\ 00221 # in a particular coordinate frame.\n\ 00222 # \n\ 00223 # sequence ID: consecutively increasing ID \n\ 00224 uint32 seq\n\ 00225 #Two-integer timestamp that is expressed as:\n\ 00226 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00227 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00228 # time-handling sugar is provided by the client library\n\ 00229 time stamp\n\ 00230 #Frame this data is associated with\n\ 00231 # 0: no frame\n\ 00232 # 1: global frame\n\ 00233 string frame_id\n\ 00234 \n\ 00235 ================================================================================\n\ 00236 MSG: geometry_msgs/Pose\n\ 00237 # A representation of pose in free space, composed of postion and orientation. \n\ 00238 Point position\n\ 00239 Quaternion orientation\n\ 00240 \n\ 00241 ================================================================================\n\ 00242 MSG: geometry_msgs/Point\n\ 00243 # This contains the position of a point in free space\n\ 00244 float64 x\n\ 00245 float64 y\n\ 00246 float64 z\n\ 00247 \n\ 00248 ================================================================================\n\ 00249 MSG: geometry_msgs/Quaternion\n\ 00250 # This represents an orientation in free space in quaternion form.\n\ 00251 \n\ 00252 float64 x\n\ 00253 float64 y\n\ 00254 float64 z\n\ 00255 float64 w\n\ 00256 \n\ 00257 ================================================================================\n\ 00258 MSG: geometry_msgs/Vector3\n\ 00259 # This represents a vector in free space. \n\ 00260 \n\ 00261 float64 x\n\ 00262 float64 y\n\ 00263 float64 z\n\ 00264 "; 00265 } 00266 00267 static const char* value(const ::object_manipulation_msgs::ClusterBoundingBox_<ContainerAllocator> &) { return value(); } 00268 }; 00269 00270 } // namespace message_traits 00271 } // namespace ros 00272 00273 namespace ros 00274 { 00275 namespace serialization 00276 { 00277 00278 template<class ContainerAllocator> struct Serializer< ::object_manipulation_msgs::ClusterBoundingBox_<ContainerAllocator> > 00279 { 00280 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00281 { 00282 stream.next(m.pose_stamped); 00283 stream.next(m.dimensions); 00284 } 00285 00286 ROS_DECLARE_ALLINONE_SERIALIZER; 00287 }; // struct ClusterBoundingBox_ 00288 } // namespace serialization 00289 } // namespace ros 00290 00291 namespace ros 00292 { 00293 namespace message_operations 00294 { 00295 00296 template<class ContainerAllocator> 00297 struct Printer< ::object_manipulation_msgs::ClusterBoundingBox_<ContainerAllocator> > 00298 { 00299 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::object_manipulation_msgs::ClusterBoundingBox_<ContainerAllocator> & v) 00300 { 00301 s << indent << "pose_stamped: "; 00302 s << std::endl; 00303 Printer< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::stream(s, indent + " ", v.pose_stamped); 00304 s << indent << "dimensions: "; 00305 s << std::endl; 00306 Printer< ::geometry_msgs::Vector3_<ContainerAllocator> >::stream(s, indent + " ", v.dimensions); 00307 } 00308 }; 00309 00310 00311 } // namespace message_operations 00312 } // namespace ros 00313 00314 #endif // OBJECT_MANIPULATION_MSGS_MESSAGE_CLUSTERBOUNDINGBOX_H 00315