00001
00002 #ifndef MANIPULATION_TRANSFORMS_SERVICE_SETINITIALTRANSFORMS_H
00003 #define MANIPULATION_TRANSFORMS_SERVICE_SETINITIALTRANSFORMS_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 #include "geometry_msgs/PoseStamped.h"
00016 #include "geometry_msgs/PoseStamped.h"
00017
00018
00019
00020 namespace manipulation_transforms
00021 {
00022 template <class ContainerAllocator>
00023 struct SetInitialTransformsRequest_ : public ros::Message
00024 {
00025 typedef SetInitialTransformsRequest_<ContainerAllocator> Type;
00026
00027 SetInitialTransformsRequest_()
00028 : object_pose()
00029 , effector_poses()
00030 {
00031 }
00032
00033 SetInitialTransformsRequest_(const ContainerAllocator& _alloc)
00034 : object_pose(_alloc)
00035 , effector_poses(_alloc)
00036 {
00037 }
00038
00039 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _object_pose_type;
00040 ::geometry_msgs::PoseStamped_<ContainerAllocator> object_pose;
00041
00042 typedef std::vector< ::geometry_msgs::PoseStamped_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::other > _effector_poses_type;
00043 std::vector< ::geometry_msgs::PoseStamped_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::other > effector_poses;
00044
00045
00046 ROS_DEPRECATED uint32_t get_effector_poses_size() const { return (uint32_t)effector_poses.size(); }
00047 ROS_DEPRECATED void set_effector_poses_size(uint32_t size) { effector_poses.resize((size_t)size); }
00048 ROS_DEPRECATED void get_effector_poses_vec(std::vector< ::geometry_msgs::PoseStamped_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::other > & vec) const { vec = this->effector_poses; }
00049 ROS_DEPRECATED void set_effector_poses_vec(const std::vector< ::geometry_msgs::PoseStamped_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::other > & vec) { this->effector_poses = vec; }
00050 private:
00051 static const char* __s_getDataType_() { return "manipulation_transforms/SetInitialTransformsRequest"; }
00052 public:
00053 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00054
00055 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00056
00057 private:
00058 static const char* __s_getMD5Sum_() { return "20e1e914372addbf166e586475963be6"; }
00059 public:
00060 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00061
00062 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00063
00064 private:
00065 static const char* __s_getServerMD5Sum_() { return "c6f24d628001d50710ead5449e25726f"; }
00066 public:
00067 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00068
00069 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00070
00071 private:
00072 static const char* __s_getMessageDefinition_() { return "geometry_msgs/PoseStamped object_pose\n\
00073 geometry_msgs/PoseStamped[] effector_poses\n\
00074 \n\
00075 ================================================================================\n\
00076 MSG: geometry_msgs/PoseStamped\n\
00077 # A Pose with reference coordinate frame and timestamp\n\
00078 Header header\n\
00079 Pose pose\n\
00080 \n\
00081 ================================================================================\n\
00082 MSG: std_msgs/Header\n\
00083 # Standard metadata for higher-level stamped data types.\n\
00084 # This is generally used to communicate timestamped data \n\
00085 # in a particular coordinate frame.\n\
00086 # \n\
00087 # sequence ID: consecutively increasing ID \n\
00088 uint32 seq\n\
00089 #Two-integer timestamp that is expressed as:\n\
00090 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00091 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00092 # time-handling sugar is provided by the client library\n\
00093 time stamp\n\
00094 #Frame this data is associated with\n\
00095 # 0: no frame\n\
00096 # 1: global frame\n\
00097 string frame_id\n\
00098 \n\
00099 ================================================================================\n\
00100 MSG: geometry_msgs/Pose\n\
00101 # A representation of pose in free space, composed of postion and orientation. \n\
00102 Point position\n\
00103 Quaternion orientation\n\
00104 \n\
00105 ================================================================================\n\
00106 MSG: geometry_msgs/Point\n\
00107 # This contains the position of a point in free space\n\
00108 float64 x\n\
00109 float64 y\n\
00110 float64 z\n\
00111 \n\
00112 ================================================================================\n\
00113 MSG: geometry_msgs/Quaternion\n\
00114 # This represents an orientation in free space in quaternion form.\n\
00115 \n\
00116 float64 x\n\
00117 float64 y\n\
00118 float64 z\n\
00119 float64 w\n\
00120 \n\
00121 "; }
00122 public:
00123 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00124
00125 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00126
00127 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00128 {
00129 ros::serialization::OStream stream(write_ptr, 1000000000);
00130 ros::serialization::serialize(stream, object_pose);
00131 ros::serialization::serialize(stream, effector_poses);
00132 return stream.getData();
00133 }
00134
00135 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00136 {
00137 ros::serialization::IStream stream(read_ptr, 1000000000);
00138 ros::serialization::deserialize(stream, object_pose);
00139 ros::serialization::deserialize(stream, effector_poses);
00140 return stream.getData();
00141 }
00142
00143 ROS_DEPRECATED virtual uint32_t serializationLength() const
00144 {
00145 uint32_t size = 0;
00146 size += ros::serialization::serializationLength(object_pose);
00147 size += ros::serialization::serializationLength(effector_poses);
00148 return size;
00149 }
00150
00151 typedef boost::shared_ptr< ::manipulation_transforms::SetInitialTransformsRequest_<ContainerAllocator> > Ptr;
00152 typedef boost::shared_ptr< ::manipulation_transforms::SetInitialTransformsRequest_<ContainerAllocator> const> ConstPtr;
00153 };
00154 typedef ::manipulation_transforms::SetInitialTransformsRequest_<std::allocator<void> > SetInitialTransformsRequest;
00155
00156 typedef boost::shared_ptr< ::manipulation_transforms::SetInitialTransformsRequest> SetInitialTransformsRequestPtr;
00157 typedef boost::shared_ptr< ::manipulation_transforms::SetInitialTransformsRequest const> SetInitialTransformsRequestConstPtr;
00158
00159
00160 template <class ContainerAllocator>
00161 struct SetInitialTransformsResponse_ : public ros::Message
00162 {
00163 typedef SetInitialTransformsResponse_<ContainerAllocator> Type;
00164
00165 SetInitialTransformsResponse_()
00166 : success(false)
00167 {
00168 }
00169
00170 SetInitialTransformsResponse_(const ContainerAllocator& _alloc)
00171 : success(false)
00172 {
00173 }
00174
00175 typedef uint8_t _success_type;
00176 uint8_t success;
00177
00178
00179 private:
00180 static const char* __s_getDataType_() { return "manipulation_transforms/SetInitialTransformsResponse"; }
00181 public:
00182 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00183
00184 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00185
00186 private:
00187 static const char* __s_getMD5Sum_() { return "358e233cde0c8a8bcfea4ce193f8fc15"; }
00188 public:
00189 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00190
00191 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00192
00193 private:
00194 static const char* __s_getServerMD5Sum_() { return "c6f24d628001d50710ead5449e25726f"; }
00195 public:
00196 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00197
00198 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00199
00200 private:
00201 static const char* __s_getMessageDefinition_() { return "\n\
00202 bool success\n\
00203 \n\
00204 \n\
00205 "; }
00206 public:
00207 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00208
00209 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00210
00211 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00212 {
00213 ros::serialization::OStream stream(write_ptr, 1000000000);
00214 ros::serialization::serialize(stream, success);
00215 return stream.getData();
00216 }
00217
00218 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00219 {
00220 ros::serialization::IStream stream(read_ptr, 1000000000);
00221 ros::serialization::deserialize(stream, success);
00222 return stream.getData();
00223 }
00224
00225 ROS_DEPRECATED virtual uint32_t serializationLength() const
00226 {
00227 uint32_t size = 0;
00228 size += ros::serialization::serializationLength(success);
00229 return size;
00230 }
00231
00232 typedef boost::shared_ptr< ::manipulation_transforms::SetInitialTransformsResponse_<ContainerAllocator> > Ptr;
00233 typedef boost::shared_ptr< ::manipulation_transforms::SetInitialTransformsResponse_<ContainerAllocator> const> ConstPtr;
00234 };
00235 typedef ::manipulation_transforms::SetInitialTransformsResponse_<std::allocator<void> > SetInitialTransformsResponse;
00236
00237 typedef boost::shared_ptr< ::manipulation_transforms::SetInitialTransformsResponse> SetInitialTransformsResponsePtr;
00238 typedef boost::shared_ptr< ::manipulation_transforms::SetInitialTransformsResponse const> SetInitialTransformsResponseConstPtr;
00239
00240 struct SetInitialTransforms
00241 {
00242
00243 typedef SetInitialTransformsRequest Request;
00244 typedef SetInitialTransformsResponse Response;
00245 Request request;
00246 Response response;
00247
00248 typedef Request RequestType;
00249 typedef Response ResponseType;
00250 };
00251 }
00252
00253 namespace ros
00254 {
00255 namespace message_traits
00256 {
00257 template<class ContainerAllocator>
00258 struct MD5Sum< ::manipulation_transforms::SetInitialTransformsRequest_<ContainerAllocator> > {
00259 static const char* value()
00260 {
00261 return "20e1e914372addbf166e586475963be6";
00262 }
00263
00264 static const char* value(const ::manipulation_transforms::SetInitialTransformsRequest_<ContainerAllocator> &) { return value(); }
00265 static const uint64_t static_value1 = 0x20e1e914372addbfULL;
00266 static const uint64_t static_value2 = 0x166e586475963be6ULL;
00267 };
00268
00269 template<class ContainerAllocator>
00270 struct DataType< ::manipulation_transforms::SetInitialTransformsRequest_<ContainerAllocator> > {
00271 static const char* value()
00272 {
00273 return "manipulation_transforms/SetInitialTransformsRequest";
00274 }
00275
00276 static const char* value(const ::manipulation_transforms::SetInitialTransformsRequest_<ContainerAllocator> &) { return value(); }
00277 };
00278
00279 template<class ContainerAllocator>
00280 struct Definition< ::manipulation_transforms::SetInitialTransformsRequest_<ContainerAllocator> > {
00281 static const char* value()
00282 {
00283 return "geometry_msgs/PoseStamped object_pose\n\
00284 geometry_msgs/PoseStamped[] effector_poses\n\
00285 \n\
00286 ================================================================================\n\
00287 MSG: geometry_msgs/PoseStamped\n\
00288 # A Pose with reference coordinate frame and timestamp\n\
00289 Header header\n\
00290 Pose pose\n\
00291 \n\
00292 ================================================================================\n\
00293 MSG: std_msgs/Header\n\
00294 # Standard metadata for higher-level stamped data types.\n\
00295 # This is generally used to communicate timestamped data \n\
00296 # in a particular coordinate frame.\n\
00297 # \n\
00298 # sequence ID: consecutively increasing ID \n\
00299 uint32 seq\n\
00300 #Two-integer timestamp that is expressed as:\n\
00301 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00302 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00303 # time-handling sugar is provided by the client library\n\
00304 time stamp\n\
00305 #Frame this data is associated with\n\
00306 # 0: no frame\n\
00307 # 1: global frame\n\
00308 string frame_id\n\
00309 \n\
00310 ================================================================================\n\
00311 MSG: geometry_msgs/Pose\n\
00312 # A representation of pose in free space, composed of postion and orientation. \n\
00313 Point position\n\
00314 Quaternion orientation\n\
00315 \n\
00316 ================================================================================\n\
00317 MSG: geometry_msgs/Point\n\
00318 # This contains the position of a point in free space\n\
00319 float64 x\n\
00320 float64 y\n\
00321 float64 z\n\
00322 \n\
00323 ================================================================================\n\
00324 MSG: geometry_msgs/Quaternion\n\
00325 # This represents an orientation in free space in quaternion form.\n\
00326 \n\
00327 float64 x\n\
00328 float64 y\n\
00329 float64 z\n\
00330 float64 w\n\
00331 \n\
00332 ";
00333 }
00334
00335 static const char* value(const ::manipulation_transforms::SetInitialTransformsRequest_<ContainerAllocator> &) { return value(); }
00336 };
00337
00338 }
00339 }
00340
00341
00342 namespace ros
00343 {
00344 namespace message_traits
00345 {
00346 template<class ContainerAllocator>
00347 struct MD5Sum< ::manipulation_transforms::SetInitialTransformsResponse_<ContainerAllocator> > {
00348 static const char* value()
00349 {
00350 return "358e233cde0c8a8bcfea4ce193f8fc15";
00351 }
00352
00353 static const char* value(const ::manipulation_transforms::SetInitialTransformsResponse_<ContainerAllocator> &) { return value(); }
00354 static const uint64_t static_value1 = 0x358e233cde0c8a8bULL;
00355 static const uint64_t static_value2 = 0xcfea4ce193f8fc15ULL;
00356 };
00357
00358 template<class ContainerAllocator>
00359 struct DataType< ::manipulation_transforms::SetInitialTransformsResponse_<ContainerAllocator> > {
00360 static const char* value()
00361 {
00362 return "manipulation_transforms/SetInitialTransformsResponse";
00363 }
00364
00365 static const char* value(const ::manipulation_transforms::SetInitialTransformsResponse_<ContainerAllocator> &) { return value(); }
00366 };
00367
00368 template<class ContainerAllocator>
00369 struct Definition< ::manipulation_transforms::SetInitialTransformsResponse_<ContainerAllocator> > {
00370 static const char* value()
00371 {
00372 return "\n\
00373 bool success\n\
00374 \n\
00375 \n\
00376 ";
00377 }
00378
00379 static const char* value(const ::manipulation_transforms::SetInitialTransformsResponse_<ContainerAllocator> &) { return value(); }
00380 };
00381
00382 template<class ContainerAllocator> struct IsFixedSize< ::manipulation_transforms::SetInitialTransformsResponse_<ContainerAllocator> > : public TrueType {};
00383 }
00384 }
00385
00386 namespace ros
00387 {
00388 namespace serialization
00389 {
00390
00391 template<class ContainerAllocator> struct Serializer< ::manipulation_transforms::SetInitialTransformsRequest_<ContainerAllocator> >
00392 {
00393 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00394 {
00395 stream.next(m.object_pose);
00396 stream.next(m.effector_poses);
00397 }
00398
00399 ROS_DECLARE_ALLINONE_SERIALIZER;
00400 };
00401 }
00402 }
00403
00404
00405 namespace ros
00406 {
00407 namespace serialization
00408 {
00409
00410 template<class ContainerAllocator> struct Serializer< ::manipulation_transforms::SetInitialTransformsResponse_<ContainerAllocator> >
00411 {
00412 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00413 {
00414 stream.next(m.success);
00415 }
00416
00417 ROS_DECLARE_ALLINONE_SERIALIZER;
00418 };
00419 }
00420 }
00421
00422 namespace ros
00423 {
00424 namespace service_traits
00425 {
00426 template<>
00427 struct MD5Sum<manipulation_transforms::SetInitialTransforms> {
00428 static const char* value()
00429 {
00430 return "c6f24d628001d50710ead5449e25726f";
00431 }
00432
00433 static const char* value(const manipulation_transforms::SetInitialTransforms&) { return value(); }
00434 };
00435
00436 template<>
00437 struct DataType<manipulation_transforms::SetInitialTransforms> {
00438 static const char* value()
00439 {
00440 return "manipulation_transforms/SetInitialTransforms";
00441 }
00442
00443 static const char* value(const manipulation_transforms::SetInitialTransforms&) { return value(); }
00444 };
00445
00446 template<class ContainerAllocator>
00447 struct MD5Sum<manipulation_transforms::SetInitialTransformsRequest_<ContainerAllocator> > {
00448 static const char* value()
00449 {
00450 return "c6f24d628001d50710ead5449e25726f";
00451 }
00452
00453 static const char* value(const manipulation_transforms::SetInitialTransformsRequest_<ContainerAllocator> &) { return value(); }
00454 };
00455
00456 template<class ContainerAllocator>
00457 struct DataType<manipulation_transforms::SetInitialTransformsRequest_<ContainerAllocator> > {
00458 static const char* value()
00459 {
00460 return "manipulation_transforms/SetInitialTransforms";
00461 }
00462
00463 static const char* value(const manipulation_transforms::SetInitialTransformsRequest_<ContainerAllocator> &) { return value(); }
00464 };
00465
00466 template<class ContainerAllocator>
00467 struct MD5Sum<manipulation_transforms::SetInitialTransformsResponse_<ContainerAllocator> > {
00468 static const char* value()
00469 {
00470 return "c6f24d628001d50710ead5449e25726f";
00471 }
00472
00473 static const char* value(const manipulation_transforms::SetInitialTransformsResponse_<ContainerAllocator> &) { return value(); }
00474 };
00475
00476 template<class ContainerAllocator>
00477 struct DataType<manipulation_transforms::SetInitialTransformsResponse_<ContainerAllocator> > {
00478 static const char* value()
00479 {
00480 return "manipulation_transforms/SetInitialTransforms";
00481 }
00482
00483 static const char* value(const manipulation_transforms::SetInitialTransformsResponse_<ContainerAllocator> &) { return value(); }
00484 };
00485
00486 }
00487 }
00488
00489 #endif // MANIPULATION_TRANSFORMS_SERVICE_SETINITIALTRANSFORMS_H
00490