00001
00002 #ifndef COB_SRVS_SERVICE_SETJOINTSTIFFNESS_H
00003 #define COB_SRVS_SERVICE_SETJOINTSTIFFNESS_H
00004 #include <string>
00005 #include <vector>
00006 #include <ostream>
00007 #include "ros/serialization.h"
00008 #include "ros/builtin_message_traits.h"
00009 #include "ros/message_operations.h"
00010 #include "ros/message.h"
00011 #include "ros/time.h"
00012
00013 #include "ros/service_traits.h"
00014
00015
00016
00017 #include "std_msgs/Bool.h"
00018 #include "std_msgs/String.h"
00019
00020 namespace cob_srvs
00021 {
00022 template <class ContainerAllocator>
00023 struct SetJointStiffnessRequest_ : public ros::Message
00024 {
00025 typedef SetJointStiffnessRequest_<ContainerAllocator> Type;
00026
00027 SetJointStiffnessRequest_()
00028 : joint_stiffness()
00029 {
00030 }
00031
00032 SetJointStiffnessRequest_(const ContainerAllocator& _alloc)
00033 : joint_stiffness(_alloc)
00034 {
00035 }
00036
00037 typedef std::vector<float, typename ContainerAllocator::template rebind<float>::other > _joint_stiffness_type;
00038 std::vector<float, typename ContainerAllocator::template rebind<float>::other > joint_stiffness;
00039
00040
00041 ROS_DEPRECATED uint32_t get_joint_stiffness_size() const { return (uint32_t)joint_stiffness.size(); }
00042 ROS_DEPRECATED void set_joint_stiffness_size(uint32_t size) { joint_stiffness.resize((size_t)size); }
00043 ROS_DEPRECATED void get_joint_stiffness_vec(std::vector<float, typename ContainerAllocator::template rebind<float>::other > & vec) const { vec = this->joint_stiffness; }
00044 ROS_DEPRECATED void set_joint_stiffness_vec(const std::vector<float, typename ContainerAllocator::template rebind<float>::other > & vec) { this->joint_stiffness = vec; }
00045 private:
00046 static const char* __s_getDataType_() { return "cob_srvs/SetJointStiffnessRequest"; }
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 "3f30c4d99702f028fe1bef65668a3d21"; }
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_getServerMD5Sum_() { return "2ae9ddd5d3294ccf3c876d966e4e11a3"; }
00061 public:
00062 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00063
00064 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00065
00066 private:
00067 static const char* __s_getMessageDefinition_() { return "float32[] joint_stiffness\n\
00068 \n\
00069 "; }
00070 public:
00071 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00072
00073 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00074
00075 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00076 {
00077 ros::serialization::OStream stream(write_ptr, 1000000000);
00078 ros::serialization::serialize(stream, joint_stiffness);
00079 return stream.getData();
00080 }
00081
00082 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00083 {
00084 ros::serialization::IStream stream(read_ptr, 1000000000);
00085 ros::serialization::deserialize(stream, joint_stiffness);
00086 return stream.getData();
00087 }
00088
00089 ROS_DEPRECATED virtual uint32_t serializationLength() const
00090 {
00091 uint32_t size = 0;
00092 size += ros::serialization::serializationLength(joint_stiffness);
00093 return size;
00094 }
00095
00096 typedef boost::shared_ptr< ::cob_srvs::SetJointStiffnessRequest_<ContainerAllocator> > Ptr;
00097 typedef boost::shared_ptr< ::cob_srvs::SetJointStiffnessRequest_<ContainerAllocator> const> ConstPtr;
00098 };
00099 typedef ::cob_srvs::SetJointStiffnessRequest_<std::allocator<void> > SetJointStiffnessRequest;
00100
00101 typedef boost::shared_ptr< ::cob_srvs::SetJointStiffnessRequest> SetJointStiffnessRequestPtr;
00102 typedef boost::shared_ptr< ::cob_srvs::SetJointStiffnessRequest const> SetJointStiffnessRequestConstPtr;
00103
00104
00105 template <class ContainerAllocator>
00106 struct SetJointStiffnessResponse_ : public ros::Message
00107 {
00108 typedef SetJointStiffnessResponse_<ContainerAllocator> Type;
00109
00110 SetJointStiffnessResponse_()
00111 : success()
00112 , error_message()
00113 {
00114 }
00115
00116 SetJointStiffnessResponse_(const ContainerAllocator& _alloc)
00117 : success(_alloc)
00118 , error_message(_alloc)
00119 {
00120 }
00121
00122 typedef ::std_msgs::Bool_<ContainerAllocator> _success_type;
00123 ::std_msgs::Bool_<ContainerAllocator> success;
00124
00125 typedef ::std_msgs::String_<ContainerAllocator> _error_message_type;
00126 ::std_msgs::String_<ContainerAllocator> error_message;
00127
00128
00129 private:
00130 static const char* __s_getDataType_() { return "cob_srvs/SetJointStiffnessResponse"; }
00131 public:
00132 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00133
00134 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00135
00136 private:
00137 static const char* __s_getMD5Sum_() { return "bdad515e8f4c013bd650d3407753d2b8"; }
00138 public:
00139 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00140
00141 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00142
00143 private:
00144 static const char* __s_getServerMD5Sum_() { return "2ae9ddd5d3294ccf3c876d966e4e11a3"; }
00145 public:
00146 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00147
00148 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00149
00150 private:
00151 static const char* __s_getMessageDefinition_() { return "std_msgs/Bool success\n\
00152 std_msgs/String error_message\n\
00153 \n\
00154 \n\
00155 ================================================================================\n\
00156 MSG: std_msgs/Bool\n\
00157 bool data\n\
00158 ================================================================================\n\
00159 MSG: std_msgs/String\n\
00160 string data\n\
00161 \n\
00162 "; }
00163 public:
00164 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00165
00166 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00167
00168 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00169 {
00170 ros::serialization::OStream stream(write_ptr, 1000000000);
00171 ros::serialization::serialize(stream, success);
00172 ros::serialization::serialize(stream, error_message);
00173 return stream.getData();
00174 }
00175
00176 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00177 {
00178 ros::serialization::IStream stream(read_ptr, 1000000000);
00179 ros::serialization::deserialize(stream, success);
00180 ros::serialization::deserialize(stream, error_message);
00181 return stream.getData();
00182 }
00183
00184 ROS_DEPRECATED virtual uint32_t serializationLength() const
00185 {
00186 uint32_t size = 0;
00187 size += ros::serialization::serializationLength(success);
00188 size += ros::serialization::serializationLength(error_message);
00189 return size;
00190 }
00191
00192 typedef boost::shared_ptr< ::cob_srvs::SetJointStiffnessResponse_<ContainerAllocator> > Ptr;
00193 typedef boost::shared_ptr< ::cob_srvs::SetJointStiffnessResponse_<ContainerAllocator> const> ConstPtr;
00194 };
00195 typedef ::cob_srvs::SetJointStiffnessResponse_<std::allocator<void> > SetJointStiffnessResponse;
00196
00197 typedef boost::shared_ptr< ::cob_srvs::SetJointStiffnessResponse> SetJointStiffnessResponsePtr;
00198 typedef boost::shared_ptr< ::cob_srvs::SetJointStiffnessResponse const> SetJointStiffnessResponseConstPtr;
00199
00200 struct SetJointStiffness
00201 {
00202
00203 typedef SetJointStiffnessRequest Request;
00204 typedef SetJointStiffnessResponse Response;
00205 Request request;
00206 Response response;
00207
00208 typedef Request RequestType;
00209 typedef Response ResponseType;
00210 };
00211 }
00212
00213 namespace ros
00214 {
00215 namespace message_traits
00216 {
00217 template<class ContainerAllocator>
00218 struct MD5Sum< ::cob_srvs::SetJointStiffnessRequest_<ContainerAllocator> > {
00219 static const char* value()
00220 {
00221 return "3f30c4d99702f028fe1bef65668a3d21";
00222 }
00223
00224 static const char* value(const ::cob_srvs::SetJointStiffnessRequest_<ContainerAllocator> &) { return value(); }
00225 static const uint64_t static_value1 = 0x3f30c4d99702f028ULL;
00226 static const uint64_t static_value2 = 0xfe1bef65668a3d21ULL;
00227 };
00228
00229 template<class ContainerAllocator>
00230 struct DataType< ::cob_srvs::SetJointStiffnessRequest_<ContainerAllocator> > {
00231 static const char* value()
00232 {
00233 return "cob_srvs/SetJointStiffnessRequest";
00234 }
00235
00236 static const char* value(const ::cob_srvs::SetJointStiffnessRequest_<ContainerAllocator> &) { return value(); }
00237 };
00238
00239 template<class ContainerAllocator>
00240 struct Definition< ::cob_srvs::SetJointStiffnessRequest_<ContainerAllocator> > {
00241 static const char* value()
00242 {
00243 return "float32[] joint_stiffness\n\
00244 \n\
00245 ";
00246 }
00247
00248 static const char* value(const ::cob_srvs::SetJointStiffnessRequest_<ContainerAllocator> &) { return value(); }
00249 };
00250
00251 }
00252 }
00253
00254
00255 namespace ros
00256 {
00257 namespace message_traits
00258 {
00259 template<class ContainerAllocator>
00260 struct MD5Sum< ::cob_srvs::SetJointStiffnessResponse_<ContainerAllocator> > {
00261 static const char* value()
00262 {
00263 return "bdad515e8f4c013bd650d3407753d2b8";
00264 }
00265
00266 static const char* value(const ::cob_srvs::SetJointStiffnessResponse_<ContainerAllocator> &) { return value(); }
00267 static const uint64_t static_value1 = 0xbdad515e8f4c013bULL;
00268 static const uint64_t static_value2 = 0xd650d3407753d2b8ULL;
00269 };
00270
00271 template<class ContainerAllocator>
00272 struct DataType< ::cob_srvs::SetJointStiffnessResponse_<ContainerAllocator> > {
00273 static const char* value()
00274 {
00275 return "cob_srvs/SetJointStiffnessResponse";
00276 }
00277
00278 static const char* value(const ::cob_srvs::SetJointStiffnessResponse_<ContainerAllocator> &) { return value(); }
00279 };
00280
00281 template<class ContainerAllocator>
00282 struct Definition< ::cob_srvs::SetJointStiffnessResponse_<ContainerAllocator> > {
00283 static const char* value()
00284 {
00285 return "std_msgs/Bool success\n\
00286 std_msgs/String error_message\n\
00287 \n\
00288 \n\
00289 ================================================================================\n\
00290 MSG: std_msgs/Bool\n\
00291 bool data\n\
00292 ================================================================================\n\
00293 MSG: std_msgs/String\n\
00294 string data\n\
00295 \n\
00296 ";
00297 }
00298
00299 static const char* value(const ::cob_srvs::SetJointStiffnessResponse_<ContainerAllocator> &) { return value(); }
00300 };
00301
00302 }
00303 }
00304
00305 namespace ros
00306 {
00307 namespace serialization
00308 {
00309
00310 template<class ContainerAllocator> struct Serializer< ::cob_srvs::SetJointStiffnessRequest_<ContainerAllocator> >
00311 {
00312 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00313 {
00314 stream.next(m.joint_stiffness);
00315 }
00316
00317 ROS_DECLARE_ALLINONE_SERIALIZER;
00318 };
00319 }
00320 }
00321
00322
00323 namespace ros
00324 {
00325 namespace serialization
00326 {
00327
00328 template<class ContainerAllocator> struct Serializer< ::cob_srvs::SetJointStiffnessResponse_<ContainerAllocator> >
00329 {
00330 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00331 {
00332 stream.next(m.success);
00333 stream.next(m.error_message);
00334 }
00335
00336 ROS_DECLARE_ALLINONE_SERIALIZER;
00337 };
00338 }
00339 }
00340
00341 namespace ros
00342 {
00343 namespace service_traits
00344 {
00345 template<>
00346 struct MD5Sum<cob_srvs::SetJointStiffness> {
00347 static const char* value()
00348 {
00349 return "2ae9ddd5d3294ccf3c876d966e4e11a3";
00350 }
00351
00352 static const char* value(const cob_srvs::SetJointStiffness&) { return value(); }
00353 };
00354
00355 template<>
00356 struct DataType<cob_srvs::SetJointStiffness> {
00357 static const char* value()
00358 {
00359 return "cob_srvs/SetJointStiffness";
00360 }
00361
00362 static const char* value(const cob_srvs::SetJointStiffness&) { return value(); }
00363 };
00364
00365 template<class ContainerAllocator>
00366 struct MD5Sum<cob_srvs::SetJointStiffnessRequest_<ContainerAllocator> > {
00367 static const char* value()
00368 {
00369 return "2ae9ddd5d3294ccf3c876d966e4e11a3";
00370 }
00371
00372 static const char* value(const cob_srvs::SetJointStiffnessRequest_<ContainerAllocator> &) { return value(); }
00373 };
00374
00375 template<class ContainerAllocator>
00376 struct DataType<cob_srvs::SetJointStiffnessRequest_<ContainerAllocator> > {
00377 static const char* value()
00378 {
00379 return "cob_srvs/SetJointStiffness";
00380 }
00381
00382 static const char* value(const cob_srvs::SetJointStiffnessRequest_<ContainerAllocator> &) { return value(); }
00383 };
00384
00385 template<class ContainerAllocator>
00386 struct MD5Sum<cob_srvs::SetJointStiffnessResponse_<ContainerAllocator> > {
00387 static const char* value()
00388 {
00389 return "2ae9ddd5d3294ccf3c876d966e4e11a3";
00390 }
00391
00392 static const char* value(const cob_srvs::SetJointStiffnessResponse_<ContainerAllocator> &) { return value(); }
00393 };
00394
00395 template<class ContainerAllocator>
00396 struct DataType<cob_srvs::SetJointStiffnessResponse_<ContainerAllocator> > {
00397 static const char* value()
00398 {
00399 return "cob_srvs/SetJointStiffness";
00400 }
00401
00402 static const char* value(const cob_srvs::SetJointStiffnessResponse_<ContainerAllocator> &) { return value(); }
00403 };
00404
00405 }
00406 }
00407
00408 #endif // COB_SRVS_SERVICE_SETJOINTSTIFFNESS_H
00409