$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-cob_common/doc_stacks/2013-03-01_14-38-37.978792/cob_common/cob_srvs/srv/SetJointTrajectory.srv */ 00002 #ifndef COB_SRVS_SERVICE_SETJOINTTRAJECTORY_H 00003 #define COB_SRVS_SERVICE_SETJOINTTRAJECTORY_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 "trajectory_msgs/JointTrajectory.h" 00020 00021 00022 #include "std_msgs/String.h" 00023 00024 namespace cob_srvs 00025 { 00026 template <class ContainerAllocator> 00027 struct SetJointTrajectoryRequest_ { 00028 typedef SetJointTrajectoryRequest_<ContainerAllocator> Type; 00029 00030 SetJointTrajectoryRequest_() 00031 : trajectory() 00032 { 00033 } 00034 00035 SetJointTrajectoryRequest_(const ContainerAllocator& _alloc) 00036 : trajectory(_alloc) 00037 { 00038 } 00039 00040 typedef ::trajectory_msgs::JointTrajectory_<ContainerAllocator> _trajectory_type; 00041 ::trajectory_msgs::JointTrajectory_<ContainerAllocator> trajectory; 00042 00043 00044 private: 00045 static const char* __s_getDataType_() { return "cob_srvs/SetJointTrajectoryRequest"; } 00046 public: 00047 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00048 00049 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00050 00051 private: 00052 static const char* __s_getMD5Sum_() { return "48a668811b715b51af6b3383511ae27f"; } 00053 public: 00054 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00055 00056 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00057 00058 private: 00059 static const char* __s_getServerMD5Sum_() { return "09ae52e52b4c7dae8badb976ba693ba3"; } 00060 public: 00061 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00062 00063 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00064 00065 private: 00066 static const char* __s_getMessageDefinition_() { return "trajectory_msgs/JointTrajectory trajectory\n\ 00067 \n\ 00068 ================================================================================\n\ 00069 MSG: trajectory_msgs/JointTrajectory\n\ 00070 Header header\n\ 00071 string[] joint_names\n\ 00072 JointTrajectoryPoint[] points\n\ 00073 ================================================================================\n\ 00074 MSG: std_msgs/Header\n\ 00075 # Standard metadata for higher-level stamped data types.\n\ 00076 # This is generally used to communicate timestamped data \n\ 00077 # in a particular coordinate frame.\n\ 00078 # \n\ 00079 # sequence ID: consecutively increasing ID \n\ 00080 uint32 seq\n\ 00081 #Two-integer timestamp that is expressed as:\n\ 00082 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00083 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00084 # time-handling sugar is provided by the client library\n\ 00085 time stamp\n\ 00086 #Frame this data is associated with\n\ 00087 # 0: no frame\n\ 00088 # 1: global frame\n\ 00089 string frame_id\n\ 00090 \n\ 00091 ================================================================================\n\ 00092 MSG: trajectory_msgs/JointTrajectoryPoint\n\ 00093 float64[] positions\n\ 00094 float64[] velocities\n\ 00095 float64[] accelerations\n\ 00096 duration time_from_start\n\ 00097 "; } 00098 public: 00099 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00100 00101 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00102 00103 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00104 { 00105 ros::serialization::OStream stream(write_ptr, 1000000000); 00106 ros::serialization::serialize(stream, trajectory); 00107 return stream.getData(); 00108 } 00109 00110 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00111 { 00112 ros::serialization::IStream stream(read_ptr, 1000000000); 00113 ros::serialization::deserialize(stream, trajectory); 00114 return stream.getData(); 00115 } 00116 00117 ROS_DEPRECATED virtual uint32_t serializationLength() const 00118 { 00119 uint32_t size = 0; 00120 size += ros::serialization::serializationLength(trajectory); 00121 return size; 00122 } 00123 00124 typedef boost::shared_ptr< ::cob_srvs::SetJointTrajectoryRequest_<ContainerAllocator> > Ptr; 00125 typedef boost::shared_ptr< ::cob_srvs::SetJointTrajectoryRequest_<ContainerAllocator> const> ConstPtr; 00126 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00127 }; // struct SetJointTrajectoryRequest 00128 typedef ::cob_srvs::SetJointTrajectoryRequest_<std::allocator<void> > SetJointTrajectoryRequest; 00129 00130 typedef boost::shared_ptr< ::cob_srvs::SetJointTrajectoryRequest> SetJointTrajectoryRequestPtr; 00131 typedef boost::shared_ptr< ::cob_srvs::SetJointTrajectoryRequest const> SetJointTrajectoryRequestConstPtr; 00132 00133 00134 template <class ContainerAllocator> 00135 struct SetJointTrajectoryResponse_ { 00136 typedef SetJointTrajectoryResponse_<ContainerAllocator> Type; 00137 00138 SetJointTrajectoryResponse_() 00139 : success(0) 00140 , errorMessage() 00141 { 00142 } 00143 00144 SetJointTrajectoryResponse_(const ContainerAllocator& _alloc) 00145 : success(0) 00146 , errorMessage(_alloc) 00147 { 00148 } 00149 00150 typedef int64_t _success_type; 00151 int64_t success; 00152 00153 typedef ::std_msgs::String_<ContainerAllocator> _errorMessage_type; 00154 ::std_msgs::String_<ContainerAllocator> errorMessage; 00155 00156 00157 private: 00158 static const char* __s_getDataType_() { return "cob_srvs/SetJointTrajectoryResponse"; } 00159 public: 00160 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00161 00162 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00163 00164 private: 00165 static const char* __s_getMD5Sum_() { return "fff2fd61c570b3016de5f27e6dc433be"; } 00166 public: 00167 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00168 00169 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00170 00171 private: 00172 static const char* __s_getServerMD5Sum_() { return "09ae52e52b4c7dae8badb976ba693ba3"; } 00173 public: 00174 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00175 00176 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00177 00178 private: 00179 static const char* __s_getMessageDefinition_() { return "int64 success\n\ 00180 std_msgs/String errorMessage\n\ 00181 \n\ 00182 \n\ 00183 ================================================================================\n\ 00184 MSG: std_msgs/String\n\ 00185 string data\n\ 00186 \n\ 00187 "; } 00188 public: 00189 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00190 00191 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00192 00193 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00194 { 00195 ros::serialization::OStream stream(write_ptr, 1000000000); 00196 ros::serialization::serialize(stream, success); 00197 ros::serialization::serialize(stream, errorMessage); 00198 return stream.getData(); 00199 } 00200 00201 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00202 { 00203 ros::serialization::IStream stream(read_ptr, 1000000000); 00204 ros::serialization::deserialize(stream, success); 00205 ros::serialization::deserialize(stream, errorMessage); 00206 return stream.getData(); 00207 } 00208 00209 ROS_DEPRECATED virtual uint32_t serializationLength() const 00210 { 00211 uint32_t size = 0; 00212 size += ros::serialization::serializationLength(success); 00213 size += ros::serialization::serializationLength(errorMessage); 00214 return size; 00215 } 00216 00217 typedef boost::shared_ptr< ::cob_srvs::SetJointTrajectoryResponse_<ContainerAllocator> > Ptr; 00218 typedef boost::shared_ptr< ::cob_srvs::SetJointTrajectoryResponse_<ContainerAllocator> const> ConstPtr; 00219 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00220 }; // struct SetJointTrajectoryResponse 00221 typedef ::cob_srvs::SetJointTrajectoryResponse_<std::allocator<void> > SetJointTrajectoryResponse; 00222 00223 typedef boost::shared_ptr< ::cob_srvs::SetJointTrajectoryResponse> SetJointTrajectoryResponsePtr; 00224 typedef boost::shared_ptr< ::cob_srvs::SetJointTrajectoryResponse const> SetJointTrajectoryResponseConstPtr; 00225 00226 struct SetJointTrajectory 00227 { 00228 00229 typedef SetJointTrajectoryRequest Request; 00230 typedef SetJointTrajectoryResponse Response; 00231 Request request; 00232 Response response; 00233 00234 typedef Request RequestType; 00235 typedef Response ResponseType; 00236 }; // struct SetJointTrajectory 00237 } // namespace cob_srvs 00238 00239 namespace ros 00240 { 00241 namespace message_traits 00242 { 00243 template<class ContainerAllocator> struct IsMessage< ::cob_srvs::SetJointTrajectoryRequest_<ContainerAllocator> > : public TrueType {}; 00244 template<class ContainerAllocator> struct IsMessage< ::cob_srvs::SetJointTrajectoryRequest_<ContainerAllocator> const> : public TrueType {}; 00245 template<class ContainerAllocator> 00246 struct MD5Sum< ::cob_srvs::SetJointTrajectoryRequest_<ContainerAllocator> > { 00247 static const char* value() 00248 { 00249 return "48a668811b715b51af6b3383511ae27f"; 00250 } 00251 00252 static const char* value(const ::cob_srvs::SetJointTrajectoryRequest_<ContainerAllocator> &) { return value(); } 00253 static const uint64_t static_value1 = 0x48a668811b715b51ULL; 00254 static const uint64_t static_value2 = 0xaf6b3383511ae27fULL; 00255 }; 00256 00257 template<class ContainerAllocator> 00258 struct DataType< ::cob_srvs::SetJointTrajectoryRequest_<ContainerAllocator> > { 00259 static const char* value() 00260 { 00261 return "cob_srvs/SetJointTrajectoryRequest"; 00262 } 00263 00264 static const char* value(const ::cob_srvs::SetJointTrajectoryRequest_<ContainerAllocator> &) { return value(); } 00265 }; 00266 00267 template<class ContainerAllocator> 00268 struct Definition< ::cob_srvs::SetJointTrajectoryRequest_<ContainerAllocator> > { 00269 static const char* value() 00270 { 00271 return "trajectory_msgs/JointTrajectory trajectory\n\ 00272 \n\ 00273 ================================================================================\n\ 00274 MSG: trajectory_msgs/JointTrajectory\n\ 00275 Header header\n\ 00276 string[] joint_names\n\ 00277 JointTrajectoryPoint[] points\n\ 00278 ================================================================================\n\ 00279 MSG: std_msgs/Header\n\ 00280 # Standard metadata for higher-level stamped data types.\n\ 00281 # This is generally used to communicate timestamped data \n\ 00282 # in a particular coordinate frame.\n\ 00283 # \n\ 00284 # sequence ID: consecutively increasing ID \n\ 00285 uint32 seq\n\ 00286 #Two-integer timestamp that is expressed as:\n\ 00287 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00288 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00289 # time-handling sugar is provided by the client library\n\ 00290 time stamp\n\ 00291 #Frame this data is associated with\n\ 00292 # 0: no frame\n\ 00293 # 1: global frame\n\ 00294 string frame_id\n\ 00295 \n\ 00296 ================================================================================\n\ 00297 MSG: trajectory_msgs/JointTrajectoryPoint\n\ 00298 float64[] positions\n\ 00299 float64[] velocities\n\ 00300 float64[] accelerations\n\ 00301 duration time_from_start\n\ 00302 "; 00303 } 00304 00305 static const char* value(const ::cob_srvs::SetJointTrajectoryRequest_<ContainerAllocator> &) { return value(); } 00306 }; 00307 00308 } // namespace message_traits 00309 } // namespace ros 00310 00311 00312 namespace ros 00313 { 00314 namespace message_traits 00315 { 00316 template<class ContainerAllocator> struct IsMessage< ::cob_srvs::SetJointTrajectoryResponse_<ContainerAllocator> > : public TrueType {}; 00317 template<class ContainerAllocator> struct IsMessage< ::cob_srvs::SetJointTrajectoryResponse_<ContainerAllocator> const> : public TrueType {}; 00318 template<class ContainerAllocator> 00319 struct MD5Sum< ::cob_srvs::SetJointTrajectoryResponse_<ContainerAllocator> > { 00320 static const char* value() 00321 { 00322 return "fff2fd61c570b3016de5f27e6dc433be"; 00323 } 00324 00325 static const char* value(const ::cob_srvs::SetJointTrajectoryResponse_<ContainerAllocator> &) { return value(); } 00326 static const uint64_t static_value1 = 0xfff2fd61c570b301ULL; 00327 static const uint64_t static_value2 = 0x6de5f27e6dc433beULL; 00328 }; 00329 00330 template<class ContainerAllocator> 00331 struct DataType< ::cob_srvs::SetJointTrajectoryResponse_<ContainerAllocator> > { 00332 static const char* value() 00333 { 00334 return "cob_srvs/SetJointTrajectoryResponse"; 00335 } 00336 00337 static const char* value(const ::cob_srvs::SetJointTrajectoryResponse_<ContainerAllocator> &) { return value(); } 00338 }; 00339 00340 template<class ContainerAllocator> 00341 struct Definition< ::cob_srvs::SetJointTrajectoryResponse_<ContainerAllocator> > { 00342 static const char* value() 00343 { 00344 return "int64 success\n\ 00345 std_msgs/String errorMessage\n\ 00346 \n\ 00347 \n\ 00348 ================================================================================\n\ 00349 MSG: std_msgs/String\n\ 00350 string data\n\ 00351 \n\ 00352 "; 00353 } 00354 00355 static const char* value(const ::cob_srvs::SetJointTrajectoryResponse_<ContainerAllocator> &) { return value(); } 00356 }; 00357 00358 } // namespace message_traits 00359 } // namespace ros 00360 00361 namespace ros 00362 { 00363 namespace serialization 00364 { 00365 00366 template<class ContainerAllocator> struct Serializer< ::cob_srvs::SetJointTrajectoryRequest_<ContainerAllocator> > 00367 { 00368 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00369 { 00370 stream.next(m.trajectory); 00371 } 00372 00373 ROS_DECLARE_ALLINONE_SERIALIZER; 00374 }; // struct SetJointTrajectoryRequest_ 00375 } // namespace serialization 00376 } // namespace ros 00377 00378 00379 namespace ros 00380 { 00381 namespace serialization 00382 { 00383 00384 template<class ContainerAllocator> struct Serializer< ::cob_srvs::SetJointTrajectoryResponse_<ContainerAllocator> > 00385 { 00386 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00387 { 00388 stream.next(m.success); 00389 stream.next(m.errorMessage); 00390 } 00391 00392 ROS_DECLARE_ALLINONE_SERIALIZER; 00393 }; // struct SetJointTrajectoryResponse_ 00394 } // namespace serialization 00395 } // namespace ros 00396 00397 namespace ros 00398 { 00399 namespace service_traits 00400 { 00401 template<> 00402 struct MD5Sum<cob_srvs::SetJointTrajectory> { 00403 static const char* value() 00404 { 00405 return "09ae52e52b4c7dae8badb976ba693ba3"; 00406 } 00407 00408 static const char* value(const cob_srvs::SetJointTrajectory&) { return value(); } 00409 }; 00410 00411 template<> 00412 struct DataType<cob_srvs::SetJointTrajectory> { 00413 static const char* value() 00414 { 00415 return "cob_srvs/SetJointTrajectory"; 00416 } 00417 00418 static const char* value(const cob_srvs::SetJointTrajectory&) { return value(); } 00419 }; 00420 00421 template<class ContainerAllocator> 00422 struct MD5Sum<cob_srvs::SetJointTrajectoryRequest_<ContainerAllocator> > { 00423 static const char* value() 00424 { 00425 return "09ae52e52b4c7dae8badb976ba693ba3"; 00426 } 00427 00428 static const char* value(const cob_srvs::SetJointTrajectoryRequest_<ContainerAllocator> &) { return value(); } 00429 }; 00430 00431 template<class ContainerAllocator> 00432 struct DataType<cob_srvs::SetJointTrajectoryRequest_<ContainerAllocator> > { 00433 static const char* value() 00434 { 00435 return "cob_srvs/SetJointTrajectory"; 00436 } 00437 00438 static const char* value(const cob_srvs::SetJointTrajectoryRequest_<ContainerAllocator> &) { return value(); } 00439 }; 00440 00441 template<class ContainerAllocator> 00442 struct MD5Sum<cob_srvs::SetJointTrajectoryResponse_<ContainerAllocator> > { 00443 static const char* value() 00444 { 00445 return "09ae52e52b4c7dae8badb976ba693ba3"; 00446 } 00447 00448 static const char* value(const cob_srvs::SetJointTrajectoryResponse_<ContainerAllocator> &) { return value(); } 00449 }; 00450 00451 template<class ContainerAllocator> 00452 struct DataType<cob_srvs::SetJointTrajectoryResponse_<ContainerAllocator> > { 00453 static const char* value() 00454 { 00455 return "cob_srvs/SetJointTrajectory"; 00456 } 00457 00458 static const char* value(const cob_srvs::SetJointTrajectoryResponse_<ContainerAllocator> &) { return value(); } 00459 }; 00460 00461 } // namespace service_traits 00462 } // namespace ros 00463 00464 #endif // COB_SRVS_SERVICE_SETJOINTTRAJECTORY_H 00465