$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-srs_public/doc_stacks/2013-03-05_12-22-34.333426/srs_public/srs_interaction_primitives/srv/AddPlanePolygon.srv */ 00002 #ifndef SRS_INTERACTION_PRIMITIVES_SERVICE_ADDPLANEPOLYGON_H 00003 #define SRS_INTERACTION_PRIMITIVES_SERVICE_ADDPLANEPOLYGON_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/Polygon.h" 00020 #include "geometry_msgs/Vector3.h" 00021 #include "std_msgs/ColorRGBA.h" 00022 00023 00024 00025 namespace srs_interaction_primitives 00026 { 00027 template <class ContainerAllocator> 00028 struct AddPlanePolygonRequest_ { 00029 typedef AddPlanePolygonRequest_<ContainerAllocator> Type; 00030 00031 AddPlanePolygonRequest_() 00032 : frame_id() 00033 , name() 00034 , description() 00035 , polygon() 00036 , normal() 00037 , color() 00038 { 00039 } 00040 00041 AddPlanePolygonRequest_(const ContainerAllocator& _alloc) 00042 : frame_id(_alloc) 00043 , name(_alloc) 00044 , description(_alloc) 00045 , polygon(_alloc) 00046 , normal(_alloc) 00047 , color(_alloc) 00048 { 00049 } 00050 00051 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _frame_id_type; 00052 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > frame_id; 00053 00054 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _name_type; 00055 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > name; 00056 00057 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _description_type; 00058 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > description; 00059 00060 typedef ::geometry_msgs::Polygon_<ContainerAllocator> _polygon_type; 00061 ::geometry_msgs::Polygon_<ContainerAllocator> polygon; 00062 00063 typedef ::geometry_msgs::Vector3_<ContainerAllocator> _normal_type; 00064 ::geometry_msgs::Vector3_<ContainerAllocator> normal; 00065 00066 typedef ::std_msgs::ColorRGBA_<ContainerAllocator> _color_type; 00067 ::std_msgs::ColorRGBA_<ContainerAllocator> color; 00068 00069 00070 private: 00071 static const char* __s_getDataType_() { return "srs_interaction_primitives/AddPlanePolygonRequest"; } 00072 public: 00073 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00074 00075 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00076 00077 private: 00078 static const char* __s_getMD5Sum_() { return "52416ef28e63eb5b9faef6901725ba3c"; } 00079 public: 00080 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00081 00082 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00083 00084 private: 00085 static const char* __s_getServerMD5Sum_() { return "52416ef28e63eb5b9faef6901725ba3c"; } 00086 public: 00087 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00088 00089 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00090 00091 private: 00092 static const char* __s_getMessageDefinition_() { return "string frame_id\n\ 00093 string name\n\ 00094 string description\n\ 00095 geometry_msgs/Polygon polygon\n\ 00096 geometry_msgs/Vector3 normal\n\ 00097 std_msgs/ColorRGBA color\n\ 00098 \n\ 00099 ================================================================================\n\ 00100 MSG: geometry_msgs/Polygon\n\ 00101 #A specification of a polygon where the first and last points are assumed to be connected\n\ 00102 geometry_msgs/Point32[] points\n\ 00103 \n\ 00104 ================================================================================\n\ 00105 MSG: geometry_msgs/Point32\n\ 00106 # This contains the position of a point in free space(with 32 bits of precision).\n\ 00107 # It is recommeded to use Point wherever possible instead of Point32. \n\ 00108 # \n\ 00109 # This recommendation is to promote interoperability. \n\ 00110 #\n\ 00111 # This message is designed to take up less space when sending\n\ 00112 # lots of points at once, as in the case of a PointCloud. \n\ 00113 \n\ 00114 float32 x\n\ 00115 float32 y\n\ 00116 float32 z\n\ 00117 ================================================================================\n\ 00118 MSG: geometry_msgs/Vector3\n\ 00119 # This represents a vector in free space. \n\ 00120 \n\ 00121 float64 x\n\ 00122 float64 y\n\ 00123 float64 z\n\ 00124 ================================================================================\n\ 00125 MSG: std_msgs/ColorRGBA\n\ 00126 float32 r\n\ 00127 float32 g\n\ 00128 float32 b\n\ 00129 float32 a\n\ 00130 \n\ 00131 "; } 00132 public: 00133 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00134 00135 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00136 00137 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00138 { 00139 ros::serialization::OStream stream(write_ptr, 1000000000); 00140 ros::serialization::serialize(stream, frame_id); 00141 ros::serialization::serialize(stream, name); 00142 ros::serialization::serialize(stream, description); 00143 ros::serialization::serialize(stream, polygon); 00144 ros::serialization::serialize(stream, normal); 00145 ros::serialization::serialize(stream, color); 00146 return stream.getData(); 00147 } 00148 00149 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00150 { 00151 ros::serialization::IStream stream(read_ptr, 1000000000); 00152 ros::serialization::deserialize(stream, frame_id); 00153 ros::serialization::deserialize(stream, name); 00154 ros::serialization::deserialize(stream, description); 00155 ros::serialization::deserialize(stream, polygon); 00156 ros::serialization::deserialize(stream, normal); 00157 ros::serialization::deserialize(stream, color); 00158 return stream.getData(); 00159 } 00160 00161 ROS_DEPRECATED virtual uint32_t serializationLength() const 00162 { 00163 uint32_t size = 0; 00164 size += ros::serialization::serializationLength(frame_id); 00165 size += ros::serialization::serializationLength(name); 00166 size += ros::serialization::serializationLength(description); 00167 size += ros::serialization::serializationLength(polygon); 00168 size += ros::serialization::serializationLength(normal); 00169 size += ros::serialization::serializationLength(color); 00170 return size; 00171 } 00172 00173 typedef boost::shared_ptr< ::srs_interaction_primitives::AddPlanePolygonRequest_<ContainerAllocator> > Ptr; 00174 typedef boost::shared_ptr< ::srs_interaction_primitives::AddPlanePolygonRequest_<ContainerAllocator> const> ConstPtr; 00175 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00176 }; // struct AddPlanePolygonRequest 00177 typedef ::srs_interaction_primitives::AddPlanePolygonRequest_<std::allocator<void> > AddPlanePolygonRequest; 00178 00179 typedef boost::shared_ptr< ::srs_interaction_primitives::AddPlanePolygonRequest> AddPlanePolygonRequestPtr; 00180 typedef boost::shared_ptr< ::srs_interaction_primitives::AddPlanePolygonRequest const> AddPlanePolygonRequestConstPtr; 00181 00182 00183 template <class ContainerAllocator> 00184 struct AddPlanePolygonResponse_ { 00185 typedef AddPlanePolygonResponse_<ContainerAllocator> Type; 00186 00187 AddPlanePolygonResponse_() 00188 { 00189 } 00190 00191 AddPlanePolygonResponse_(const ContainerAllocator& _alloc) 00192 { 00193 } 00194 00195 00196 private: 00197 static const char* __s_getDataType_() { return "srs_interaction_primitives/AddPlanePolygonResponse"; } 00198 public: 00199 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00200 00201 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00202 00203 private: 00204 static const char* __s_getMD5Sum_() { return "d41d8cd98f00b204e9800998ecf8427e"; } 00205 public: 00206 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00207 00208 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00209 00210 private: 00211 static const char* __s_getServerMD5Sum_() { return "52416ef28e63eb5b9faef6901725ba3c"; } 00212 public: 00213 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00214 00215 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00216 00217 private: 00218 static const char* __s_getMessageDefinition_() { return "\n\ 00219 \n\ 00220 "; } 00221 public: 00222 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00223 00224 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00225 00226 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00227 { 00228 ros::serialization::OStream stream(write_ptr, 1000000000); 00229 return stream.getData(); 00230 } 00231 00232 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00233 { 00234 ros::serialization::IStream stream(read_ptr, 1000000000); 00235 return stream.getData(); 00236 } 00237 00238 ROS_DEPRECATED virtual uint32_t serializationLength() const 00239 { 00240 uint32_t size = 0; 00241 return size; 00242 } 00243 00244 typedef boost::shared_ptr< ::srs_interaction_primitives::AddPlanePolygonResponse_<ContainerAllocator> > Ptr; 00245 typedef boost::shared_ptr< ::srs_interaction_primitives::AddPlanePolygonResponse_<ContainerAllocator> const> ConstPtr; 00246 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00247 }; // struct AddPlanePolygonResponse 00248 typedef ::srs_interaction_primitives::AddPlanePolygonResponse_<std::allocator<void> > AddPlanePolygonResponse; 00249 00250 typedef boost::shared_ptr< ::srs_interaction_primitives::AddPlanePolygonResponse> AddPlanePolygonResponsePtr; 00251 typedef boost::shared_ptr< ::srs_interaction_primitives::AddPlanePolygonResponse const> AddPlanePolygonResponseConstPtr; 00252 00253 struct AddPlanePolygon 00254 { 00255 00256 typedef AddPlanePolygonRequest Request; 00257 typedef AddPlanePolygonResponse Response; 00258 Request request; 00259 Response response; 00260 00261 typedef Request RequestType; 00262 typedef Response ResponseType; 00263 }; // struct AddPlanePolygon 00264 } // namespace srs_interaction_primitives 00265 00266 namespace ros 00267 { 00268 namespace message_traits 00269 { 00270 template<class ContainerAllocator> struct IsMessage< ::srs_interaction_primitives::AddPlanePolygonRequest_<ContainerAllocator> > : public TrueType {}; 00271 template<class ContainerAllocator> struct IsMessage< ::srs_interaction_primitives::AddPlanePolygonRequest_<ContainerAllocator> const> : public TrueType {}; 00272 template<class ContainerAllocator> 00273 struct MD5Sum< ::srs_interaction_primitives::AddPlanePolygonRequest_<ContainerAllocator> > { 00274 static const char* value() 00275 { 00276 return "52416ef28e63eb5b9faef6901725ba3c"; 00277 } 00278 00279 static const char* value(const ::srs_interaction_primitives::AddPlanePolygonRequest_<ContainerAllocator> &) { return value(); } 00280 static const uint64_t static_value1 = 0x52416ef28e63eb5bULL; 00281 static const uint64_t static_value2 = 0x9faef6901725ba3cULL; 00282 }; 00283 00284 template<class ContainerAllocator> 00285 struct DataType< ::srs_interaction_primitives::AddPlanePolygonRequest_<ContainerAllocator> > { 00286 static const char* value() 00287 { 00288 return "srs_interaction_primitives/AddPlanePolygonRequest"; 00289 } 00290 00291 static const char* value(const ::srs_interaction_primitives::AddPlanePolygonRequest_<ContainerAllocator> &) { return value(); } 00292 }; 00293 00294 template<class ContainerAllocator> 00295 struct Definition< ::srs_interaction_primitives::AddPlanePolygonRequest_<ContainerAllocator> > { 00296 static const char* value() 00297 { 00298 return "string frame_id\n\ 00299 string name\n\ 00300 string description\n\ 00301 geometry_msgs/Polygon polygon\n\ 00302 geometry_msgs/Vector3 normal\n\ 00303 std_msgs/ColorRGBA color\n\ 00304 \n\ 00305 ================================================================================\n\ 00306 MSG: geometry_msgs/Polygon\n\ 00307 #A specification of a polygon where the first and last points are assumed to be connected\n\ 00308 geometry_msgs/Point32[] points\n\ 00309 \n\ 00310 ================================================================================\n\ 00311 MSG: geometry_msgs/Point32\n\ 00312 # This contains the position of a point in free space(with 32 bits of precision).\n\ 00313 # It is recommeded to use Point wherever possible instead of Point32. \n\ 00314 # \n\ 00315 # This recommendation is to promote interoperability. \n\ 00316 #\n\ 00317 # This message is designed to take up less space when sending\n\ 00318 # lots of points at once, as in the case of a PointCloud. \n\ 00319 \n\ 00320 float32 x\n\ 00321 float32 y\n\ 00322 float32 z\n\ 00323 ================================================================================\n\ 00324 MSG: geometry_msgs/Vector3\n\ 00325 # This represents a vector in free space. \n\ 00326 \n\ 00327 float64 x\n\ 00328 float64 y\n\ 00329 float64 z\n\ 00330 ================================================================================\n\ 00331 MSG: std_msgs/ColorRGBA\n\ 00332 float32 r\n\ 00333 float32 g\n\ 00334 float32 b\n\ 00335 float32 a\n\ 00336 \n\ 00337 "; 00338 } 00339 00340 static const char* value(const ::srs_interaction_primitives::AddPlanePolygonRequest_<ContainerAllocator> &) { return value(); } 00341 }; 00342 00343 } // namespace message_traits 00344 } // namespace ros 00345 00346 00347 namespace ros 00348 { 00349 namespace message_traits 00350 { 00351 template<class ContainerAllocator> struct IsMessage< ::srs_interaction_primitives::AddPlanePolygonResponse_<ContainerAllocator> > : public TrueType {}; 00352 template<class ContainerAllocator> struct IsMessage< ::srs_interaction_primitives::AddPlanePolygonResponse_<ContainerAllocator> const> : public TrueType {}; 00353 template<class ContainerAllocator> 00354 struct MD5Sum< ::srs_interaction_primitives::AddPlanePolygonResponse_<ContainerAllocator> > { 00355 static const char* value() 00356 { 00357 return "d41d8cd98f00b204e9800998ecf8427e"; 00358 } 00359 00360 static const char* value(const ::srs_interaction_primitives::AddPlanePolygonResponse_<ContainerAllocator> &) { return value(); } 00361 static const uint64_t static_value1 = 0xd41d8cd98f00b204ULL; 00362 static const uint64_t static_value2 = 0xe9800998ecf8427eULL; 00363 }; 00364 00365 template<class ContainerAllocator> 00366 struct DataType< ::srs_interaction_primitives::AddPlanePolygonResponse_<ContainerAllocator> > { 00367 static const char* value() 00368 { 00369 return "srs_interaction_primitives/AddPlanePolygonResponse"; 00370 } 00371 00372 static const char* value(const ::srs_interaction_primitives::AddPlanePolygonResponse_<ContainerAllocator> &) { return value(); } 00373 }; 00374 00375 template<class ContainerAllocator> 00376 struct Definition< ::srs_interaction_primitives::AddPlanePolygonResponse_<ContainerAllocator> > { 00377 static const char* value() 00378 { 00379 return "\n\ 00380 \n\ 00381 "; 00382 } 00383 00384 static const char* value(const ::srs_interaction_primitives::AddPlanePolygonResponse_<ContainerAllocator> &) { return value(); } 00385 }; 00386 00387 template<class ContainerAllocator> struct IsFixedSize< ::srs_interaction_primitives::AddPlanePolygonResponse_<ContainerAllocator> > : public TrueType {}; 00388 } // namespace message_traits 00389 } // namespace ros 00390 00391 namespace ros 00392 { 00393 namespace serialization 00394 { 00395 00396 template<class ContainerAllocator> struct Serializer< ::srs_interaction_primitives::AddPlanePolygonRequest_<ContainerAllocator> > 00397 { 00398 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00399 { 00400 stream.next(m.frame_id); 00401 stream.next(m.name); 00402 stream.next(m.description); 00403 stream.next(m.polygon); 00404 stream.next(m.normal); 00405 stream.next(m.color); 00406 } 00407 00408 ROS_DECLARE_ALLINONE_SERIALIZER; 00409 }; // struct AddPlanePolygonRequest_ 00410 } // namespace serialization 00411 } // namespace ros 00412 00413 00414 namespace ros 00415 { 00416 namespace serialization 00417 { 00418 00419 template<class ContainerAllocator> struct Serializer< ::srs_interaction_primitives::AddPlanePolygonResponse_<ContainerAllocator> > 00420 { 00421 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00422 { 00423 } 00424 00425 ROS_DECLARE_ALLINONE_SERIALIZER; 00426 }; // struct AddPlanePolygonResponse_ 00427 } // namespace serialization 00428 } // namespace ros 00429 00430 namespace ros 00431 { 00432 namespace service_traits 00433 { 00434 template<> 00435 struct MD5Sum<srs_interaction_primitives::AddPlanePolygon> { 00436 static const char* value() 00437 { 00438 return "52416ef28e63eb5b9faef6901725ba3c"; 00439 } 00440 00441 static const char* value(const srs_interaction_primitives::AddPlanePolygon&) { return value(); } 00442 }; 00443 00444 template<> 00445 struct DataType<srs_interaction_primitives::AddPlanePolygon> { 00446 static const char* value() 00447 { 00448 return "srs_interaction_primitives/AddPlanePolygon"; 00449 } 00450 00451 static const char* value(const srs_interaction_primitives::AddPlanePolygon&) { return value(); } 00452 }; 00453 00454 template<class ContainerAllocator> 00455 struct MD5Sum<srs_interaction_primitives::AddPlanePolygonRequest_<ContainerAllocator> > { 00456 static const char* value() 00457 { 00458 return "52416ef28e63eb5b9faef6901725ba3c"; 00459 } 00460 00461 static const char* value(const srs_interaction_primitives::AddPlanePolygonRequest_<ContainerAllocator> &) { return value(); } 00462 }; 00463 00464 template<class ContainerAllocator> 00465 struct DataType<srs_interaction_primitives::AddPlanePolygonRequest_<ContainerAllocator> > { 00466 static const char* value() 00467 { 00468 return "srs_interaction_primitives/AddPlanePolygon"; 00469 } 00470 00471 static const char* value(const srs_interaction_primitives::AddPlanePolygonRequest_<ContainerAllocator> &) { return value(); } 00472 }; 00473 00474 template<class ContainerAllocator> 00475 struct MD5Sum<srs_interaction_primitives::AddPlanePolygonResponse_<ContainerAllocator> > { 00476 static const char* value() 00477 { 00478 return "52416ef28e63eb5b9faef6901725ba3c"; 00479 } 00480 00481 static const char* value(const srs_interaction_primitives::AddPlanePolygonResponse_<ContainerAllocator> &) { return value(); } 00482 }; 00483 00484 template<class ContainerAllocator> 00485 struct DataType<srs_interaction_primitives::AddPlanePolygonResponse_<ContainerAllocator> > { 00486 static const char* value() 00487 { 00488 return "srs_interaction_primitives/AddPlanePolygon"; 00489 } 00490 00491 static const char* value(const srs_interaction_primitives::AddPlanePolygonResponse_<ContainerAllocator> &) { return value(); } 00492 }; 00493 00494 } // namespace service_traits 00495 } // namespace ros 00496 00497 #endif // SRS_INTERACTION_PRIMITIVES_SERVICE_ADDPLANEPOLYGON_H 00498