00001
00002 #ifndef WVIZ_KINEMATIC_MANAGER_SERVICE_GETPOSE_H
00003 #define WVIZ_KINEMATIC_MANAGER_SERVICE_GETPOSE_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/Pose.h"
00016
00017
00018 #include "geometry_msgs/PoseStamped.h"
00019
00020 namespace wviz_kinematic_manager
00021 {
00022 template <class ContainerAllocator>
00023 struct getPoseRequest_ : public ros::Message
00024 {
00025 typedef getPoseRequest_<ContainerAllocator> Type;
00026
00027 getPoseRequest_()
00028 : target_links()
00029 , target_pose()
00030 {
00031 }
00032
00033 getPoseRequest_(const ContainerAllocator& _alloc)
00034 : target_links(_alloc)
00035 , target_pose(_alloc)
00036 {
00037 }
00038
00039 typedef std::vector<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > , typename ContainerAllocator::template rebind<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::other > _target_links_type;
00040 std::vector<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > , typename ContainerAllocator::template rebind<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::other > target_links;
00041
00042 typedef ::geometry_msgs::Pose_<ContainerAllocator> _target_pose_type;
00043 ::geometry_msgs::Pose_<ContainerAllocator> target_pose;
00044
00045
00046 ROS_DEPRECATED uint32_t get_target_links_size() const { return (uint32_t)target_links.size(); }
00047 ROS_DEPRECATED void set_target_links_size(uint32_t size) { target_links.resize((size_t)size); }
00048 ROS_DEPRECATED void get_target_links_vec(std::vector<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > , typename ContainerAllocator::template rebind<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::other > & vec) const { vec = this->target_links; }
00049 ROS_DEPRECATED void set_target_links_vec(const std::vector<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > , typename ContainerAllocator::template rebind<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::other > & vec) { this->target_links = vec; }
00050 private:
00051 static const char* __s_getDataType_() { return "wviz_kinematic_manager/getPoseRequest"; }
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 "7ee2fbad0c07db0b009763e855e9b2ac"; }
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 "f83421ab90906a7c0f59d3af9b0985c9"; }
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 "string[] target_links\n\
00073 geometry_msgs/Pose target_pose\n\
00074 \n\
00075 ================================================================================\n\
00076 MSG: geometry_msgs/Pose\n\
00077 # A representation of pose in free space, composed of postion and orientation. \n\
00078 Point position\n\
00079 Quaternion orientation\n\
00080 \n\
00081 ================================================================================\n\
00082 MSG: geometry_msgs/Point\n\
00083 # This contains the position of a point in free space\n\
00084 float64 x\n\
00085 float64 y\n\
00086 float64 z\n\
00087 \n\
00088 ================================================================================\n\
00089 MSG: geometry_msgs/Quaternion\n\
00090 # This represents an orientation in free space in quaternion form.\n\
00091 \n\
00092 float64 x\n\
00093 float64 y\n\
00094 float64 z\n\
00095 float64 w\n\
00096 \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, target_links);
00107 ros::serialization::serialize(stream, target_pose);
00108 return stream.getData();
00109 }
00110
00111 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00112 {
00113 ros::serialization::IStream stream(read_ptr, 1000000000);
00114 ros::serialization::deserialize(stream, target_links);
00115 ros::serialization::deserialize(stream, target_pose);
00116 return stream.getData();
00117 }
00118
00119 ROS_DEPRECATED virtual uint32_t serializationLength() const
00120 {
00121 uint32_t size = 0;
00122 size += ros::serialization::serializationLength(target_links);
00123 size += ros::serialization::serializationLength(target_pose);
00124 return size;
00125 }
00126
00127 typedef boost::shared_ptr< ::wviz_kinematic_manager::getPoseRequest_<ContainerAllocator> > Ptr;
00128 typedef boost::shared_ptr< ::wviz_kinematic_manager::getPoseRequest_<ContainerAllocator> const> ConstPtr;
00129 };
00130 typedef ::wviz_kinematic_manager::getPoseRequest_<std::allocator<void> > getPoseRequest;
00131
00132 typedef boost::shared_ptr< ::wviz_kinematic_manager::getPoseRequest> getPoseRequestPtr;
00133 typedef boost::shared_ptr< ::wviz_kinematic_manager::getPoseRequest const> getPoseRequestConstPtr;
00134
00135
00136 template <class ContainerAllocator>
00137 struct getPoseResponse_ : public ros::Message
00138 {
00139 typedef getPoseResponse_<ContainerAllocator> Type;
00140
00141 getPoseResponse_()
00142 : pose_stamped()
00143 , link_names()
00144 , error_code(0)
00145 {
00146 }
00147
00148 getPoseResponse_(const ContainerAllocator& _alloc)
00149 : pose_stamped(_alloc)
00150 , link_names(_alloc)
00151 , error_code(0)
00152 {
00153 }
00154
00155 typedef std::vector< ::geometry_msgs::PoseStamped_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::other > _pose_stamped_type;
00156 std::vector< ::geometry_msgs::PoseStamped_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::other > pose_stamped;
00157
00158 typedef std::vector<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > , typename ContainerAllocator::template rebind<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::other > _link_names_type;
00159 std::vector<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > , typename ContainerAllocator::template rebind<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::other > link_names;
00160
00161 typedef int32_t _error_code_type;
00162 int32_t error_code;
00163
00164
00165 ROS_DEPRECATED uint32_t get_pose_stamped_size() const { return (uint32_t)pose_stamped.size(); }
00166 ROS_DEPRECATED void set_pose_stamped_size(uint32_t size) { pose_stamped.resize((size_t)size); }
00167 ROS_DEPRECATED void get_pose_stamped_vec(std::vector< ::geometry_msgs::PoseStamped_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::other > & vec) const { vec = this->pose_stamped; }
00168 ROS_DEPRECATED void set_pose_stamped_vec(const std::vector< ::geometry_msgs::PoseStamped_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::other > & vec) { this->pose_stamped = vec; }
00169 ROS_DEPRECATED uint32_t get_link_names_size() const { return (uint32_t)link_names.size(); }
00170 ROS_DEPRECATED void set_link_names_size(uint32_t size) { link_names.resize((size_t)size); }
00171 ROS_DEPRECATED void get_link_names_vec(std::vector<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > , typename ContainerAllocator::template rebind<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::other > & vec) const { vec = this->link_names; }
00172 ROS_DEPRECATED void set_link_names_vec(const std::vector<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > , typename ContainerAllocator::template rebind<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::other > & vec) { this->link_names = vec; }
00173 private:
00174 static const char* __s_getDataType_() { return "wviz_kinematic_manager/getPoseResponse"; }
00175 public:
00176 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00177
00178 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00179
00180 private:
00181 static const char* __s_getMD5Sum_() { return "7451f3d6bd520fd7f0ba4283adfac02c"; }
00182 public:
00183 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00184
00185 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00186
00187 private:
00188 static const char* __s_getServerMD5Sum_() { return "f83421ab90906a7c0f59d3af9b0985c9"; }
00189 public:
00190 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00191
00192 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00193
00194 private:
00195 static const char* __s_getMessageDefinition_() { return "geometry_msgs/PoseStamped[] pose_stamped\n\
00196 string[] link_names\n\
00197 int32 error_code\n\
00198 \n\
00199 \n\
00200 ================================================================================\n\
00201 MSG: geometry_msgs/PoseStamped\n\
00202 # A Pose with reference coordinate frame and timestamp\n\
00203 Header header\n\
00204 Pose pose\n\
00205 \n\
00206 ================================================================================\n\
00207 MSG: std_msgs/Header\n\
00208 # Standard metadata for higher-level stamped data types.\n\
00209 # This is generally used to communicate timestamped data \n\
00210 # in a particular coordinate frame.\n\
00211 # \n\
00212 # sequence ID: consecutively increasing ID \n\
00213 uint32 seq\n\
00214 #Two-integer timestamp that is expressed as:\n\
00215 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00216 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00217 # time-handling sugar is provided by the client library\n\
00218 time stamp\n\
00219 #Frame this data is associated with\n\
00220 # 0: no frame\n\
00221 # 1: global frame\n\
00222 string frame_id\n\
00223 \n\
00224 ================================================================================\n\
00225 MSG: geometry_msgs/Pose\n\
00226 # A representation of pose in free space, composed of postion and orientation. \n\
00227 Point position\n\
00228 Quaternion orientation\n\
00229 \n\
00230 ================================================================================\n\
00231 MSG: geometry_msgs/Point\n\
00232 # This contains the position of a point in free space\n\
00233 float64 x\n\
00234 float64 y\n\
00235 float64 z\n\
00236 \n\
00237 ================================================================================\n\
00238 MSG: geometry_msgs/Quaternion\n\
00239 # This represents an orientation in free space in quaternion form.\n\
00240 \n\
00241 float64 x\n\
00242 float64 y\n\
00243 float64 z\n\
00244 float64 w\n\
00245 \n\
00246 "; }
00247 public:
00248 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00249
00250 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00251
00252 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00253 {
00254 ros::serialization::OStream stream(write_ptr, 1000000000);
00255 ros::serialization::serialize(stream, pose_stamped);
00256 ros::serialization::serialize(stream, link_names);
00257 ros::serialization::serialize(stream, error_code);
00258 return stream.getData();
00259 }
00260
00261 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00262 {
00263 ros::serialization::IStream stream(read_ptr, 1000000000);
00264 ros::serialization::deserialize(stream, pose_stamped);
00265 ros::serialization::deserialize(stream, link_names);
00266 ros::serialization::deserialize(stream, error_code);
00267 return stream.getData();
00268 }
00269
00270 ROS_DEPRECATED virtual uint32_t serializationLength() const
00271 {
00272 uint32_t size = 0;
00273 size += ros::serialization::serializationLength(pose_stamped);
00274 size += ros::serialization::serializationLength(link_names);
00275 size += ros::serialization::serializationLength(error_code);
00276 return size;
00277 }
00278
00279 typedef boost::shared_ptr< ::wviz_kinematic_manager::getPoseResponse_<ContainerAllocator> > Ptr;
00280 typedef boost::shared_ptr< ::wviz_kinematic_manager::getPoseResponse_<ContainerAllocator> const> ConstPtr;
00281 };
00282 typedef ::wviz_kinematic_manager::getPoseResponse_<std::allocator<void> > getPoseResponse;
00283
00284 typedef boost::shared_ptr< ::wviz_kinematic_manager::getPoseResponse> getPoseResponsePtr;
00285 typedef boost::shared_ptr< ::wviz_kinematic_manager::getPoseResponse const> getPoseResponseConstPtr;
00286
00287 struct getPose
00288 {
00289
00290 typedef getPoseRequest Request;
00291 typedef getPoseResponse Response;
00292 Request request;
00293 Response response;
00294
00295 typedef Request RequestType;
00296 typedef Response ResponseType;
00297 };
00298 }
00299
00300 namespace ros
00301 {
00302 namespace message_traits
00303 {
00304 template<class ContainerAllocator>
00305 struct MD5Sum< ::wviz_kinematic_manager::getPoseRequest_<ContainerAllocator> > {
00306 static const char* value()
00307 {
00308 return "7ee2fbad0c07db0b009763e855e9b2ac";
00309 }
00310
00311 static const char* value(const ::wviz_kinematic_manager::getPoseRequest_<ContainerAllocator> &) { return value(); }
00312 static const uint64_t static_value1 = 0x7ee2fbad0c07db0bULL;
00313 static const uint64_t static_value2 = 0x009763e855e9b2acULL;
00314 };
00315
00316 template<class ContainerAllocator>
00317 struct DataType< ::wviz_kinematic_manager::getPoseRequest_<ContainerAllocator> > {
00318 static const char* value()
00319 {
00320 return "wviz_kinematic_manager/getPoseRequest";
00321 }
00322
00323 static const char* value(const ::wviz_kinematic_manager::getPoseRequest_<ContainerAllocator> &) { return value(); }
00324 };
00325
00326 template<class ContainerAllocator>
00327 struct Definition< ::wviz_kinematic_manager::getPoseRequest_<ContainerAllocator> > {
00328 static const char* value()
00329 {
00330 return "string[] target_links\n\
00331 geometry_msgs/Pose target_pose\n\
00332 \n\
00333 ================================================================================\n\
00334 MSG: geometry_msgs/Pose\n\
00335 # A representation of pose in free space, composed of postion and orientation. \n\
00336 Point position\n\
00337 Quaternion orientation\n\
00338 \n\
00339 ================================================================================\n\
00340 MSG: geometry_msgs/Point\n\
00341 # This contains the position of a point in free space\n\
00342 float64 x\n\
00343 float64 y\n\
00344 float64 z\n\
00345 \n\
00346 ================================================================================\n\
00347 MSG: geometry_msgs/Quaternion\n\
00348 # This represents an orientation in free space in quaternion form.\n\
00349 \n\
00350 float64 x\n\
00351 float64 y\n\
00352 float64 z\n\
00353 float64 w\n\
00354 \n\
00355 ";
00356 }
00357
00358 static const char* value(const ::wviz_kinematic_manager::getPoseRequest_<ContainerAllocator> &) { return value(); }
00359 };
00360
00361 }
00362 }
00363
00364
00365 namespace ros
00366 {
00367 namespace message_traits
00368 {
00369 template<class ContainerAllocator>
00370 struct MD5Sum< ::wviz_kinematic_manager::getPoseResponse_<ContainerAllocator> > {
00371 static const char* value()
00372 {
00373 return "7451f3d6bd520fd7f0ba4283adfac02c";
00374 }
00375
00376 static const char* value(const ::wviz_kinematic_manager::getPoseResponse_<ContainerAllocator> &) { return value(); }
00377 static const uint64_t static_value1 = 0x7451f3d6bd520fd7ULL;
00378 static const uint64_t static_value2 = 0xf0ba4283adfac02cULL;
00379 };
00380
00381 template<class ContainerAllocator>
00382 struct DataType< ::wviz_kinematic_manager::getPoseResponse_<ContainerAllocator> > {
00383 static const char* value()
00384 {
00385 return "wviz_kinematic_manager/getPoseResponse";
00386 }
00387
00388 static const char* value(const ::wviz_kinematic_manager::getPoseResponse_<ContainerAllocator> &) { return value(); }
00389 };
00390
00391 template<class ContainerAllocator>
00392 struct Definition< ::wviz_kinematic_manager::getPoseResponse_<ContainerAllocator> > {
00393 static const char* value()
00394 {
00395 return "geometry_msgs/PoseStamped[] pose_stamped\n\
00396 string[] link_names\n\
00397 int32 error_code\n\
00398 \n\
00399 \n\
00400 ================================================================================\n\
00401 MSG: geometry_msgs/PoseStamped\n\
00402 # A Pose with reference coordinate frame and timestamp\n\
00403 Header header\n\
00404 Pose pose\n\
00405 \n\
00406 ================================================================================\n\
00407 MSG: std_msgs/Header\n\
00408 # Standard metadata for higher-level stamped data types.\n\
00409 # This is generally used to communicate timestamped data \n\
00410 # in a particular coordinate frame.\n\
00411 # \n\
00412 # sequence ID: consecutively increasing ID \n\
00413 uint32 seq\n\
00414 #Two-integer timestamp that is expressed as:\n\
00415 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00416 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00417 # time-handling sugar is provided by the client library\n\
00418 time stamp\n\
00419 #Frame this data is associated with\n\
00420 # 0: no frame\n\
00421 # 1: global frame\n\
00422 string frame_id\n\
00423 \n\
00424 ================================================================================\n\
00425 MSG: geometry_msgs/Pose\n\
00426 # A representation of pose in free space, composed of postion and orientation. \n\
00427 Point position\n\
00428 Quaternion orientation\n\
00429 \n\
00430 ================================================================================\n\
00431 MSG: geometry_msgs/Point\n\
00432 # This contains the position of a point in free space\n\
00433 float64 x\n\
00434 float64 y\n\
00435 float64 z\n\
00436 \n\
00437 ================================================================================\n\
00438 MSG: geometry_msgs/Quaternion\n\
00439 # This represents an orientation in free space in quaternion form.\n\
00440 \n\
00441 float64 x\n\
00442 float64 y\n\
00443 float64 z\n\
00444 float64 w\n\
00445 \n\
00446 ";
00447 }
00448
00449 static const char* value(const ::wviz_kinematic_manager::getPoseResponse_<ContainerAllocator> &) { return value(); }
00450 };
00451
00452 }
00453 }
00454
00455 namespace ros
00456 {
00457 namespace serialization
00458 {
00459
00460 template<class ContainerAllocator> struct Serializer< ::wviz_kinematic_manager::getPoseRequest_<ContainerAllocator> >
00461 {
00462 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00463 {
00464 stream.next(m.target_links);
00465 stream.next(m.target_pose);
00466 }
00467
00468 ROS_DECLARE_ALLINONE_SERIALIZER;
00469 };
00470 }
00471 }
00472
00473
00474 namespace ros
00475 {
00476 namespace serialization
00477 {
00478
00479 template<class ContainerAllocator> struct Serializer< ::wviz_kinematic_manager::getPoseResponse_<ContainerAllocator> >
00480 {
00481 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00482 {
00483 stream.next(m.pose_stamped);
00484 stream.next(m.link_names);
00485 stream.next(m.error_code);
00486 }
00487
00488 ROS_DECLARE_ALLINONE_SERIALIZER;
00489 };
00490 }
00491 }
00492
00493 namespace ros
00494 {
00495 namespace service_traits
00496 {
00497 template<>
00498 struct MD5Sum<wviz_kinematic_manager::getPose> {
00499 static const char* value()
00500 {
00501 return "f83421ab90906a7c0f59d3af9b0985c9";
00502 }
00503
00504 static const char* value(const wviz_kinematic_manager::getPose&) { return value(); }
00505 };
00506
00507 template<>
00508 struct DataType<wviz_kinematic_manager::getPose> {
00509 static const char* value()
00510 {
00511 return "wviz_kinematic_manager/getPose";
00512 }
00513
00514 static const char* value(const wviz_kinematic_manager::getPose&) { return value(); }
00515 };
00516
00517 template<class ContainerAllocator>
00518 struct MD5Sum<wviz_kinematic_manager::getPoseRequest_<ContainerAllocator> > {
00519 static const char* value()
00520 {
00521 return "f83421ab90906a7c0f59d3af9b0985c9";
00522 }
00523
00524 static const char* value(const wviz_kinematic_manager::getPoseRequest_<ContainerAllocator> &) { return value(); }
00525 };
00526
00527 template<class ContainerAllocator>
00528 struct DataType<wviz_kinematic_manager::getPoseRequest_<ContainerAllocator> > {
00529 static const char* value()
00530 {
00531 return "wviz_kinematic_manager/getPose";
00532 }
00533
00534 static const char* value(const wviz_kinematic_manager::getPoseRequest_<ContainerAllocator> &) { return value(); }
00535 };
00536
00537 template<class ContainerAllocator>
00538 struct MD5Sum<wviz_kinematic_manager::getPoseResponse_<ContainerAllocator> > {
00539 static const char* value()
00540 {
00541 return "f83421ab90906a7c0f59d3af9b0985c9";
00542 }
00543
00544 static const char* value(const wviz_kinematic_manager::getPoseResponse_<ContainerAllocator> &) { return value(); }
00545 };
00546
00547 template<class ContainerAllocator>
00548 struct DataType<wviz_kinematic_manager::getPoseResponse_<ContainerAllocator> > {
00549 static const char* value()
00550 {
00551 return "wviz_kinematic_manager/getPose";
00552 }
00553
00554 static const char* value(const wviz_kinematic_manager::getPoseResponse_<ContainerAllocator> &) { return value(); }
00555 };
00556
00557 }
00558 }
00559
00560 #endif // WVIZ_KINEMATIC_MANAGER_SERVICE_GETPOSE_H
00561