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