$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_env_model/srv/GetObjectsInSphere.srv */ 00002 #ifndef SRS_ENV_MODEL_SERVICE_GETOBJECTSINSPHERE_H 00003 #define SRS_ENV_MODEL_SERVICE_GETOBJECTSINSPHERE_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/Point.h" 00020 00021 00022 00023 namespace srs_env_model 00024 { 00025 template <class ContainerAllocator> 00026 struct GetObjectsInSphereRequest_ { 00027 typedef GetObjectsInSphereRequest_<ContainerAllocator> Type; 00028 00029 GetObjectsInSphereRequest_() 00030 : position() 00031 , radius(0.0) 00032 { 00033 } 00034 00035 GetObjectsInSphereRequest_(const ContainerAllocator& _alloc) 00036 : position(_alloc) 00037 , radius(0.0) 00038 { 00039 } 00040 00041 typedef ::geometry_msgs::Point_<ContainerAllocator> _position_type; 00042 ::geometry_msgs::Point_<ContainerAllocator> position; 00043 00044 typedef float _radius_type; 00045 float radius; 00046 00047 00048 private: 00049 static const char* __s_getDataType_() { return "srs_env_model/GetObjectsInSphereRequest"; } 00050 public: 00051 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00052 00053 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00054 00055 private: 00056 static const char* __s_getMD5Sum_() { return "d30211bfb3bb657c20b477998d440e07"; } 00057 public: 00058 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00059 00060 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00061 00062 private: 00063 static const char* __s_getServerMD5Sum_() { return "86b8af38e531b2bcc3f4d0a73a412f36"; } 00064 public: 00065 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00066 00067 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00068 00069 private: 00070 static const char* __s_getMessageDefinition_() { return "geometry_msgs/Point position\n\ 00071 float32 radius\n\ 00072 \n\ 00073 ================================================================================\n\ 00074 MSG: geometry_msgs/Point\n\ 00075 # This contains the position of a point in free space\n\ 00076 float64 x\n\ 00077 float64 y\n\ 00078 float64 z\n\ 00079 \n\ 00080 "; } 00081 public: 00082 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00083 00084 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00085 00086 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00087 { 00088 ros::serialization::OStream stream(write_ptr, 1000000000); 00089 ros::serialization::serialize(stream, position); 00090 ros::serialization::serialize(stream, radius); 00091 return stream.getData(); 00092 } 00093 00094 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00095 { 00096 ros::serialization::IStream stream(read_ptr, 1000000000); 00097 ros::serialization::deserialize(stream, position); 00098 ros::serialization::deserialize(stream, radius); 00099 return stream.getData(); 00100 } 00101 00102 ROS_DEPRECATED virtual uint32_t serializationLength() const 00103 { 00104 uint32_t size = 0; 00105 size += ros::serialization::serializationLength(position); 00106 size += ros::serialization::serializationLength(radius); 00107 return size; 00108 } 00109 00110 typedef boost::shared_ptr< ::srs_env_model::GetObjectsInSphereRequest_<ContainerAllocator> > Ptr; 00111 typedef boost::shared_ptr< ::srs_env_model::GetObjectsInSphereRequest_<ContainerAllocator> const> ConstPtr; 00112 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00113 }; // struct GetObjectsInSphereRequest 00114 typedef ::srs_env_model::GetObjectsInSphereRequest_<std::allocator<void> > GetObjectsInSphereRequest; 00115 00116 typedef boost::shared_ptr< ::srs_env_model::GetObjectsInSphereRequest> GetObjectsInSphereRequestPtr; 00117 typedef boost::shared_ptr< ::srs_env_model::GetObjectsInSphereRequest const> GetObjectsInSphereRequestConstPtr; 00118 00119 00120 template <class ContainerAllocator> 00121 struct GetObjectsInSphereResponse_ { 00122 typedef GetObjectsInSphereResponse_<ContainerAllocator> Type; 00123 00124 GetObjectsInSphereResponse_() 00125 : object_ids() 00126 { 00127 } 00128 00129 GetObjectsInSphereResponse_(const ContainerAllocator& _alloc) 00130 : object_ids(_alloc) 00131 { 00132 } 00133 00134 typedef std::vector<uint32_t, typename ContainerAllocator::template rebind<uint32_t>::other > _object_ids_type; 00135 std::vector<uint32_t, typename ContainerAllocator::template rebind<uint32_t>::other > object_ids; 00136 00137 00138 ROS_DEPRECATED uint32_t get_object_ids_size() const { return (uint32_t)object_ids.size(); } 00139 ROS_DEPRECATED void set_object_ids_size(uint32_t size) { object_ids.resize((size_t)size); } 00140 ROS_DEPRECATED void get_object_ids_vec(std::vector<uint32_t, typename ContainerAllocator::template rebind<uint32_t>::other > & vec) const { vec = this->object_ids; } 00141 ROS_DEPRECATED void set_object_ids_vec(const std::vector<uint32_t, typename ContainerAllocator::template rebind<uint32_t>::other > & vec) { this->object_ids = vec; } 00142 private: 00143 static const char* __s_getDataType_() { return "srs_env_model/GetObjectsInSphereResponse"; } 00144 public: 00145 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00146 00147 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00148 00149 private: 00150 static const char* __s_getMD5Sum_() { return "51b8c1ab69cd630e4f6eaee2d22fc8d0"; } 00151 public: 00152 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00153 00154 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00155 00156 private: 00157 static const char* __s_getServerMD5Sum_() { return "86b8af38e531b2bcc3f4d0a73a412f36"; } 00158 public: 00159 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00160 00161 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00162 00163 private: 00164 static const char* __s_getMessageDefinition_() { return "uint32[] object_ids\n\ 00165 \n\ 00166 "; } 00167 public: 00168 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00169 00170 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00171 00172 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00173 { 00174 ros::serialization::OStream stream(write_ptr, 1000000000); 00175 ros::serialization::serialize(stream, object_ids); 00176 return stream.getData(); 00177 } 00178 00179 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00180 { 00181 ros::serialization::IStream stream(read_ptr, 1000000000); 00182 ros::serialization::deserialize(stream, object_ids); 00183 return stream.getData(); 00184 } 00185 00186 ROS_DEPRECATED virtual uint32_t serializationLength() const 00187 { 00188 uint32_t size = 0; 00189 size += ros::serialization::serializationLength(object_ids); 00190 return size; 00191 } 00192 00193 typedef boost::shared_ptr< ::srs_env_model::GetObjectsInSphereResponse_<ContainerAllocator> > Ptr; 00194 typedef boost::shared_ptr< ::srs_env_model::GetObjectsInSphereResponse_<ContainerAllocator> const> ConstPtr; 00195 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00196 }; // struct GetObjectsInSphereResponse 00197 typedef ::srs_env_model::GetObjectsInSphereResponse_<std::allocator<void> > GetObjectsInSphereResponse; 00198 00199 typedef boost::shared_ptr< ::srs_env_model::GetObjectsInSphereResponse> GetObjectsInSphereResponsePtr; 00200 typedef boost::shared_ptr< ::srs_env_model::GetObjectsInSphereResponse const> GetObjectsInSphereResponseConstPtr; 00201 00202 struct GetObjectsInSphere 00203 { 00204 00205 typedef GetObjectsInSphereRequest Request; 00206 typedef GetObjectsInSphereResponse Response; 00207 Request request; 00208 Response response; 00209 00210 typedef Request RequestType; 00211 typedef Response ResponseType; 00212 }; // struct GetObjectsInSphere 00213 } // namespace srs_env_model 00214 00215 namespace ros 00216 { 00217 namespace message_traits 00218 { 00219 template<class ContainerAllocator> struct IsMessage< ::srs_env_model::GetObjectsInSphereRequest_<ContainerAllocator> > : public TrueType {}; 00220 template<class ContainerAllocator> struct IsMessage< ::srs_env_model::GetObjectsInSphereRequest_<ContainerAllocator> const> : public TrueType {}; 00221 template<class ContainerAllocator> 00222 struct MD5Sum< ::srs_env_model::GetObjectsInSphereRequest_<ContainerAllocator> > { 00223 static const char* value() 00224 { 00225 return "d30211bfb3bb657c20b477998d440e07"; 00226 } 00227 00228 static const char* value(const ::srs_env_model::GetObjectsInSphereRequest_<ContainerAllocator> &) { return value(); } 00229 static const uint64_t static_value1 = 0xd30211bfb3bb657cULL; 00230 static const uint64_t static_value2 = 0x20b477998d440e07ULL; 00231 }; 00232 00233 template<class ContainerAllocator> 00234 struct DataType< ::srs_env_model::GetObjectsInSphereRequest_<ContainerAllocator> > { 00235 static const char* value() 00236 { 00237 return "srs_env_model/GetObjectsInSphereRequest"; 00238 } 00239 00240 static const char* value(const ::srs_env_model::GetObjectsInSphereRequest_<ContainerAllocator> &) { return value(); } 00241 }; 00242 00243 template<class ContainerAllocator> 00244 struct Definition< ::srs_env_model::GetObjectsInSphereRequest_<ContainerAllocator> > { 00245 static const char* value() 00246 { 00247 return "geometry_msgs/Point position\n\ 00248 float32 radius\n\ 00249 \n\ 00250 ================================================================================\n\ 00251 MSG: geometry_msgs/Point\n\ 00252 # This contains the position of a point in free space\n\ 00253 float64 x\n\ 00254 float64 y\n\ 00255 float64 z\n\ 00256 \n\ 00257 "; 00258 } 00259 00260 static const char* value(const ::srs_env_model::GetObjectsInSphereRequest_<ContainerAllocator> &) { return value(); } 00261 }; 00262 00263 template<class ContainerAllocator> struct IsFixedSize< ::srs_env_model::GetObjectsInSphereRequest_<ContainerAllocator> > : public TrueType {}; 00264 } // namespace message_traits 00265 } // namespace ros 00266 00267 00268 namespace ros 00269 { 00270 namespace message_traits 00271 { 00272 template<class ContainerAllocator> struct IsMessage< ::srs_env_model::GetObjectsInSphereResponse_<ContainerAllocator> > : public TrueType {}; 00273 template<class ContainerAllocator> struct IsMessage< ::srs_env_model::GetObjectsInSphereResponse_<ContainerAllocator> const> : public TrueType {}; 00274 template<class ContainerAllocator> 00275 struct MD5Sum< ::srs_env_model::GetObjectsInSphereResponse_<ContainerAllocator> > { 00276 static const char* value() 00277 { 00278 return "51b8c1ab69cd630e4f6eaee2d22fc8d0"; 00279 } 00280 00281 static const char* value(const ::srs_env_model::GetObjectsInSphereResponse_<ContainerAllocator> &) { return value(); } 00282 static const uint64_t static_value1 = 0x51b8c1ab69cd630eULL; 00283 static const uint64_t static_value2 = 0x4f6eaee2d22fc8d0ULL; 00284 }; 00285 00286 template<class ContainerAllocator> 00287 struct DataType< ::srs_env_model::GetObjectsInSphereResponse_<ContainerAllocator> > { 00288 static const char* value() 00289 { 00290 return "srs_env_model/GetObjectsInSphereResponse"; 00291 } 00292 00293 static const char* value(const ::srs_env_model::GetObjectsInSphereResponse_<ContainerAllocator> &) { return value(); } 00294 }; 00295 00296 template<class ContainerAllocator> 00297 struct Definition< ::srs_env_model::GetObjectsInSphereResponse_<ContainerAllocator> > { 00298 static const char* value() 00299 { 00300 return "uint32[] object_ids\n\ 00301 \n\ 00302 "; 00303 } 00304 00305 static const char* value(const ::srs_env_model::GetObjectsInSphereResponse_<ContainerAllocator> &) { return value(); } 00306 }; 00307 00308 } // namespace message_traits 00309 } // namespace ros 00310 00311 namespace ros 00312 { 00313 namespace serialization 00314 { 00315 00316 template<class ContainerAllocator> struct Serializer< ::srs_env_model::GetObjectsInSphereRequest_<ContainerAllocator> > 00317 { 00318 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00319 { 00320 stream.next(m.position); 00321 stream.next(m.radius); 00322 } 00323 00324 ROS_DECLARE_ALLINONE_SERIALIZER; 00325 }; // struct GetObjectsInSphereRequest_ 00326 } // namespace serialization 00327 } // namespace ros 00328 00329 00330 namespace ros 00331 { 00332 namespace serialization 00333 { 00334 00335 template<class ContainerAllocator> struct Serializer< ::srs_env_model::GetObjectsInSphereResponse_<ContainerAllocator> > 00336 { 00337 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00338 { 00339 stream.next(m.object_ids); 00340 } 00341 00342 ROS_DECLARE_ALLINONE_SERIALIZER; 00343 }; // struct GetObjectsInSphereResponse_ 00344 } // namespace serialization 00345 } // namespace ros 00346 00347 namespace ros 00348 { 00349 namespace service_traits 00350 { 00351 template<> 00352 struct MD5Sum<srs_env_model::GetObjectsInSphere> { 00353 static const char* value() 00354 { 00355 return "86b8af38e531b2bcc3f4d0a73a412f36"; 00356 } 00357 00358 static const char* value(const srs_env_model::GetObjectsInSphere&) { return value(); } 00359 }; 00360 00361 template<> 00362 struct DataType<srs_env_model::GetObjectsInSphere> { 00363 static const char* value() 00364 { 00365 return "srs_env_model/GetObjectsInSphere"; 00366 } 00367 00368 static const char* value(const srs_env_model::GetObjectsInSphere&) { return value(); } 00369 }; 00370 00371 template<class ContainerAllocator> 00372 struct MD5Sum<srs_env_model::GetObjectsInSphereRequest_<ContainerAllocator> > { 00373 static const char* value() 00374 { 00375 return "86b8af38e531b2bcc3f4d0a73a412f36"; 00376 } 00377 00378 static const char* value(const srs_env_model::GetObjectsInSphereRequest_<ContainerAllocator> &) { return value(); } 00379 }; 00380 00381 template<class ContainerAllocator> 00382 struct DataType<srs_env_model::GetObjectsInSphereRequest_<ContainerAllocator> > { 00383 static const char* value() 00384 { 00385 return "srs_env_model/GetObjectsInSphere"; 00386 } 00387 00388 static const char* value(const srs_env_model::GetObjectsInSphereRequest_<ContainerAllocator> &) { return value(); } 00389 }; 00390 00391 template<class ContainerAllocator> 00392 struct MD5Sum<srs_env_model::GetObjectsInSphereResponse_<ContainerAllocator> > { 00393 static const char* value() 00394 { 00395 return "86b8af38e531b2bcc3f4d0a73a412f36"; 00396 } 00397 00398 static const char* value(const srs_env_model::GetObjectsInSphereResponse_<ContainerAllocator> &) { return value(); } 00399 }; 00400 00401 template<class ContainerAllocator> 00402 struct DataType<srs_env_model::GetObjectsInSphereResponse_<ContainerAllocator> > { 00403 static const char* value() 00404 { 00405 return "srs_env_model/GetObjectsInSphere"; 00406 } 00407 00408 static const char* value(const srs_env_model::GetObjectsInSphereResponse_<ContainerAllocator> &) { return value(); } 00409 }; 00410 00411 } // namespace service_traits 00412 } // namespace ros 00413 00414 #endif // SRS_ENV_MODEL_SERVICE_GETOBJECTSINSPHERE_H 00415