$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-pr2_arm_navigation/doc_stacks/2013-03-01_16-34-09.360918/pr2_arm_navigation/pr2_arm_navigation_perception/srv/BuildCloudAngle.srv */ 00002 #ifndef PR2_ARM_NAVIGATION_PERCEPTION_SERVICE_BUILDCLOUDANGLE_H 00003 #define PR2_ARM_NAVIGATION_PERCEPTION_SERVICE_BUILDCLOUDANGLE_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 00020 00021 #include "sensor_msgs/PointCloud.h" 00022 00023 namespace pr2_arm_navigation_perception 00024 { 00025 template <class ContainerAllocator> 00026 struct BuildCloudAngleRequest_ { 00027 typedef BuildCloudAngleRequest_<ContainerAllocator> Type; 00028 00029 BuildCloudAngleRequest_() 00030 : angle_begin(0.0) 00031 , angle_end(0.0) 00032 , duration(0.0) 00033 { 00034 } 00035 00036 BuildCloudAngleRequest_(const ContainerAllocator& _alloc) 00037 : angle_begin(0.0) 00038 , angle_end(0.0) 00039 , duration(0.0) 00040 { 00041 } 00042 00043 typedef double _angle_begin_type; 00044 double angle_begin; 00045 00046 typedef double _angle_end_type; 00047 double angle_end; 00048 00049 typedef double _duration_type; 00050 double duration; 00051 00052 00053 private: 00054 static const char* __s_getDataType_() { return "pr2_arm_navigation_perception/BuildCloudAngleRequest"; } 00055 public: 00056 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00057 00058 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00059 00060 private: 00061 static const char* __s_getMD5Sum_() { return "f30b95de7b6756e5f67b5d49f4f7affd"; } 00062 public: 00063 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00064 00065 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00066 00067 private: 00068 static const char* __s_getServerMD5Sum_() { return "7469d22e99d2e7f342cec297b7bb49d3"; } 00069 public: 00070 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00071 00072 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00073 00074 private: 00075 static const char* __s_getMessageDefinition_() { return "float64 angle_begin\n\ 00076 float64 angle_end\n\ 00077 float64 duration\n\ 00078 \n\ 00079 "; } 00080 public: 00081 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00082 00083 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00084 00085 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00086 { 00087 ros::serialization::OStream stream(write_ptr, 1000000000); 00088 ros::serialization::serialize(stream, angle_begin); 00089 ros::serialization::serialize(stream, angle_end); 00090 ros::serialization::serialize(stream, duration); 00091 return stream.getData(); 00092 } 00093 00094 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00095 { 00096 ros::serialization::IStream stream(read_ptr, 1000000000); 00097 ros::serialization::deserialize(stream, angle_begin); 00098 ros::serialization::deserialize(stream, angle_end); 00099 ros::serialization::deserialize(stream, duration); 00100 return stream.getData(); 00101 } 00102 00103 ROS_DEPRECATED virtual uint32_t serializationLength() const 00104 { 00105 uint32_t size = 0; 00106 size += ros::serialization::serializationLength(angle_begin); 00107 size += ros::serialization::serializationLength(angle_end); 00108 size += ros::serialization::serializationLength(duration); 00109 return size; 00110 } 00111 00112 typedef boost::shared_ptr< ::pr2_arm_navigation_perception::BuildCloudAngleRequest_<ContainerAllocator> > Ptr; 00113 typedef boost::shared_ptr< ::pr2_arm_navigation_perception::BuildCloudAngleRequest_<ContainerAllocator> const> ConstPtr; 00114 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00115 }; // struct BuildCloudAngleRequest 00116 typedef ::pr2_arm_navigation_perception::BuildCloudAngleRequest_<std::allocator<void> > BuildCloudAngleRequest; 00117 00118 typedef boost::shared_ptr< ::pr2_arm_navigation_perception::BuildCloudAngleRequest> BuildCloudAngleRequestPtr; 00119 typedef boost::shared_ptr< ::pr2_arm_navigation_perception::BuildCloudAngleRequest const> BuildCloudAngleRequestConstPtr; 00120 00121 00122 template <class ContainerAllocator> 00123 struct BuildCloudAngleResponse_ { 00124 typedef BuildCloudAngleResponse_<ContainerAllocator> Type; 00125 00126 BuildCloudAngleResponse_() 00127 : cloud() 00128 { 00129 } 00130 00131 BuildCloudAngleResponse_(const ContainerAllocator& _alloc) 00132 : cloud(_alloc) 00133 { 00134 } 00135 00136 typedef ::sensor_msgs::PointCloud_<ContainerAllocator> _cloud_type; 00137 ::sensor_msgs::PointCloud_<ContainerAllocator> cloud; 00138 00139 00140 private: 00141 static const char* __s_getDataType_() { return "pr2_arm_navigation_perception/BuildCloudAngleResponse"; } 00142 public: 00143 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00144 00145 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00146 00147 private: 00148 static const char* __s_getMD5Sum_() { return "4217b28a903e4ad7869a83b3653110ff"; } 00149 public: 00150 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00151 00152 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00153 00154 private: 00155 static const char* __s_getServerMD5Sum_() { return "7469d22e99d2e7f342cec297b7bb49d3"; } 00156 public: 00157 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00158 00159 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00160 00161 private: 00162 static const char* __s_getMessageDefinition_() { return "sensor_msgs/PointCloud cloud\n\ 00163 \n\ 00164 \n\ 00165 ================================================================================\n\ 00166 MSG: sensor_msgs/PointCloud\n\ 00167 # This message holds a collection of 3d points, plus optional additional\n\ 00168 # information about each point.\n\ 00169 \n\ 00170 # Time of sensor data acquisition, coordinate frame ID.\n\ 00171 Header header\n\ 00172 \n\ 00173 # Array of 3d points. Each Point32 should be interpreted as a 3d point\n\ 00174 # in the frame given in the header.\n\ 00175 geometry_msgs/Point32[] points\n\ 00176 \n\ 00177 # Each channel should have the same number of elements as points array,\n\ 00178 # and the data in each channel should correspond 1:1 with each point.\n\ 00179 # Channel names in common practice are listed in ChannelFloat32.msg.\n\ 00180 ChannelFloat32[] channels\n\ 00181 \n\ 00182 ================================================================================\n\ 00183 MSG: std_msgs/Header\n\ 00184 # Standard metadata for higher-level stamped data types.\n\ 00185 # This is generally used to communicate timestamped data \n\ 00186 # in a particular coordinate frame.\n\ 00187 # \n\ 00188 # sequence ID: consecutively increasing ID \n\ 00189 uint32 seq\n\ 00190 #Two-integer timestamp that is expressed as:\n\ 00191 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00192 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00193 # time-handling sugar is provided by the client library\n\ 00194 time stamp\n\ 00195 #Frame this data is associated with\n\ 00196 # 0: no frame\n\ 00197 # 1: global frame\n\ 00198 string frame_id\n\ 00199 \n\ 00200 ================================================================================\n\ 00201 MSG: geometry_msgs/Point32\n\ 00202 # This contains the position of a point in free space(with 32 bits of precision).\n\ 00203 # It is recommeded to use Point wherever possible instead of Point32. \n\ 00204 # \n\ 00205 # This recommendation is to promote interoperability. \n\ 00206 #\n\ 00207 # This message is designed to take up less space when sending\n\ 00208 # lots of points at once, as in the case of a PointCloud. \n\ 00209 \n\ 00210 float32 x\n\ 00211 float32 y\n\ 00212 float32 z\n\ 00213 ================================================================================\n\ 00214 MSG: sensor_msgs/ChannelFloat32\n\ 00215 # This message is used by the PointCloud message to hold optional data\n\ 00216 # associated with each point in the cloud. The length of the values\n\ 00217 # array should be the same as the length of the points array in the\n\ 00218 # PointCloud, and each value should be associated with the corresponding\n\ 00219 # point.\n\ 00220 \n\ 00221 # Channel names in existing practice include:\n\ 00222 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\ 00223 # This is opposite to usual conventions but remains for\n\ 00224 # historical reasons. The newer PointCloud2 message has no\n\ 00225 # such problem.\n\ 00226 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\ 00227 # (R,G,B) values packed into the least significant 24 bits,\n\ 00228 # in order.\n\ 00229 # \"intensity\" - laser or pixel intensity.\n\ 00230 # \"distance\"\n\ 00231 \n\ 00232 # The channel name should give semantics of the channel (e.g.\n\ 00233 # \"intensity\" instead of \"value\").\n\ 00234 string name\n\ 00235 \n\ 00236 # The values array should be 1-1 with the elements of the associated\n\ 00237 # PointCloud.\n\ 00238 float32[] values\n\ 00239 \n\ 00240 "; } 00241 public: 00242 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00243 00244 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00245 00246 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00247 { 00248 ros::serialization::OStream stream(write_ptr, 1000000000); 00249 ros::serialization::serialize(stream, cloud); 00250 return stream.getData(); 00251 } 00252 00253 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00254 { 00255 ros::serialization::IStream stream(read_ptr, 1000000000); 00256 ros::serialization::deserialize(stream, cloud); 00257 return stream.getData(); 00258 } 00259 00260 ROS_DEPRECATED virtual uint32_t serializationLength() const 00261 { 00262 uint32_t size = 0; 00263 size += ros::serialization::serializationLength(cloud); 00264 return size; 00265 } 00266 00267 typedef boost::shared_ptr< ::pr2_arm_navigation_perception::BuildCloudAngleResponse_<ContainerAllocator> > Ptr; 00268 typedef boost::shared_ptr< ::pr2_arm_navigation_perception::BuildCloudAngleResponse_<ContainerAllocator> const> ConstPtr; 00269 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00270 }; // struct BuildCloudAngleResponse 00271 typedef ::pr2_arm_navigation_perception::BuildCloudAngleResponse_<std::allocator<void> > BuildCloudAngleResponse; 00272 00273 typedef boost::shared_ptr< ::pr2_arm_navigation_perception::BuildCloudAngleResponse> BuildCloudAngleResponsePtr; 00274 typedef boost::shared_ptr< ::pr2_arm_navigation_perception::BuildCloudAngleResponse const> BuildCloudAngleResponseConstPtr; 00275 00276 struct BuildCloudAngle 00277 { 00278 00279 typedef BuildCloudAngleRequest Request; 00280 typedef BuildCloudAngleResponse Response; 00281 Request request; 00282 Response response; 00283 00284 typedef Request RequestType; 00285 typedef Response ResponseType; 00286 }; // struct BuildCloudAngle 00287 } // namespace pr2_arm_navigation_perception 00288 00289 namespace ros 00290 { 00291 namespace message_traits 00292 { 00293 template<class ContainerAllocator> struct IsMessage< ::pr2_arm_navigation_perception::BuildCloudAngleRequest_<ContainerAllocator> > : public TrueType {}; 00294 template<class ContainerAllocator> struct IsMessage< ::pr2_arm_navigation_perception::BuildCloudAngleRequest_<ContainerAllocator> const> : public TrueType {}; 00295 template<class ContainerAllocator> 00296 struct MD5Sum< ::pr2_arm_navigation_perception::BuildCloudAngleRequest_<ContainerAllocator> > { 00297 static const char* value() 00298 { 00299 return "f30b95de7b6756e5f67b5d49f4f7affd"; 00300 } 00301 00302 static const char* value(const ::pr2_arm_navigation_perception::BuildCloudAngleRequest_<ContainerAllocator> &) { return value(); } 00303 static const uint64_t static_value1 = 0xf30b95de7b6756e5ULL; 00304 static const uint64_t static_value2 = 0xf67b5d49f4f7affdULL; 00305 }; 00306 00307 template<class ContainerAllocator> 00308 struct DataType< ::pr2_arm_navigation_perception::BuildCloudAngleRequest_<ContainerAllocator> > { 00309 static const char* value() 00310 { 00311 return "pr2_arm_navigation_perception/BuildCloudAngleRequest"; 00312 } 00313 00314 static const char* value(const ::pr2_arm_navigation_perception::BuildCloudAngleRequest_<ContainerAllocator> &) { return value(); } 00315 }; 00316 00317 template<class ContainerAllocator> 00318 struct Definition< ::pr2_arm_navigation_perception::BuildCloudAngleRequest_<ContainerAllocator> > { 00319 static const char* value() 00320 { 00321 return "float64 angle_begin\n\ 00322 float64 angle_end\n\ 00323 float64 duration\n\ 00324 \n\ 00325 "; 00326 } 00327 00328 static const char* value(const ::pr2_arm_navigation_perception::BuildCloudAngleRequest_<ContainerAllocator> &) { return value(); } 00329 }; 00330 00331 template<class ContainerAllocator> struct IsFixedSize< ::pr2_arm_navigation_perception::BuildCloudAngleRequest_<ContainerAllocator> > : public TrueType {}; 00332 } // namespace message_traits 00333 } // namespace ros 00334 00335 00336 namespace ros 00337 { 00338 namespace message_traits 00339 { 00340 template<class ContainerAllocator> struct IsMessage< ::pr2_arm_navigation_perception::BuildCloudAngleResponse_<ContainerAllocator> > : public TrueType {}; 00341 template<class ContainerAllocator> struct IsMessage< ::pr2_arm_navigation_perception::BuildCloudAngleResponse_<ContainerAllocator> const> : public TrueType {}; 00342 template<class ContainerAllocator> 00343 struct MD5Sum< ::pr2_arm_navigation_perception::BuildCloudAngleResponse_<ContainerAllocator> > { 00344 static const char* value() 00345 { 00346 return "4217b28a903e4ad7869a83b3653110ff"; 00347 } 00348 00349 static const char* value(const ::pr2_arm_navigation_perception::BuildCloudAngleResponse_<ContainerAllocator> &) { return value(); } 00350 static const uint64_t static_value1 = 0x4217b28a903e4ad7ULL; 00351 static const uint64_t static_value2 = 0x869a83b3653110ffULL; 00352 }; 00353 00354 template<class ContainerAllocator> 00355 struct DataType< ::pr2_arm_navigation_perception::BuildCloudAngleResponse_<ContainerAllocator> > { 00356 static const char* value() 00357 { 00358 return "pr2_arm_navigation_perception/BuildCloudAngleResponse"; 00359 } 00360 00361 static const char* value(const ::pr2_arm_navigation_perception::BuildCloudAngleResponse_<ContainerAllocator> &) { return value(); } 00362 }; 00363 00364 template<class ContainerAllocator> 00365 struct Definition< ::pr2_arm_navigation_perception::BuildCloudAngleResponse_<ContainerAllocator> > { 00366 static const char* value() 00367 { 00368 return "sensor_msgs/PointCloud cloud\n\ 00369 \n\ 00370 \n\ 00371 ================================================================================\n\ 00372 MSG: sensor_msgs/PointCloud\n\ 00373 # This message holds a collection of 3d points, plus optional additional\n\ 00374 # information about each point.\n\ 00375 \n\ 00376 # Time of sensor data acquisition, coordinate frame ID.\n\ 00377 Header header\n\ 00378 \n\ 00379 # Array of 3d points. Each Point32 should be interpreted as a 3d point\n\ 00380 # in the frame given in the header.\n\ 00381 geometry_msgs/Point32[] points\n\ 00382 \n\ 00383 # Each channel should have the same number of elements as points array,\n\ 00384 # and the data in each channel should correspond 1:1 with each point.\n\ 00385 # Channel names in common practice are listed in ChannelFloat32.msg.\n\ 00386 ChannelFloat32[] channels\n\ 00387 \n\ 00388 ================================================================================\n\ 00389 MSG: std_msgs/Header\n\ 00390 # Standard metadata for higher-level stamped data types.\n\ 00391 # This is generally used to communicate timestamped data \n\ 00392 # in a particular coordinate frame.\n\ 00393 # \n\ 00394 # sequence ID: consecutively increasing ID \n\ 00395 uint32 seq\n\ 00396 #Two-integer timestamp that is expressed as:\n\ 00397 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00398 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00399 # time-handling sugar is provided by the client library\n\ 00400 time stamp\n\ 00401 #Frame this data is associated with\n\ 00402 # 0: no frame\n\ 00403 # 1: global frame\n\ 00404 string frame_id\n\ 00405 \n\ 00406 ================================================================================\n\ 00407 MSG: geometry_msgs/Point32\n\ 00408 # This contains the position of a point in free space(with 32 bits of precision).\n\ 00409 # It is recommeded to use Point wherever possible instead of Point32. \n\ 00410 # \n\ 00411 # This recommendation is to promote interoperability. \n\ 00412 #\n\ 00413 # This message is designed to take up less space when sending\n\ 00414 # lots of points at once, as in the case of a PointCloud. \n\ 00415 \n\ 00416 float32 x\n\ 00417 float32 y\n\ 00418 float32 z\n\ 00419 ================================================================================\n\ 00420 MSG: sensor_msgs/ChannelFloat32\n\ 00421 # This message is used by the PointCloud message to hold optional data\n\ 00422 # associated with each point in the cloud. The length of the values\n\ 00423 # array should be the same as the length of the points array in the\n\ 00424 # PointCloud, and each value should be associated with the corresponding\n\ 00425 # point.\n\ 00426 \n\ 00427 # Channel names in existing practice include:\n\ 00428 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\ 00429 # This is opposite to usual conventions but remains for\n\ 00430 # historical reasons. The newer PointCloud2 message has no\n\ 00431 # such problem.\n\ 00432 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\ 00433 # (R,G,B) values packed into the least significant 24 bits,\n\ 00434 # in order.\n\ 00435 # \"intensity\" - laser or pixel intensity.\n\ 00436 # \"distance\"\n\ 00437 \n\ 00438 # The channel name should give semantics of the channel (e.g.\n\ 00439 # \"intensity\" instead of \"value\").\n\ 00440 string name\n\ 00441 \n\ 00442 # The values array should be 1-1 with the elements of the associated\n\ 00443 # PointCloud.\n\ 00444 float32[] values\n\ 00445 \n\ 00446 "; 00447 } 00448 00449 static const char* value(const ::pr2_arm_navigation_perception::BuildCloudAngleResponse_<ContainerAllocator> &) { return value(); } 00450 }; 00451 00452 } // namespace message_traits 00453 } // namespace ros 00454 00455 namespace ros 00456 { 00457 namespace serialization 00458 { 00459 00460 template<class ContainerAllocator> struct Serializer< ::pr2_arm_navigation_perception::BuildCloudAngleRequest_<ContainerAllocator> > 00461 { 00462 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00463 { 00464 stream.next(m.angle_begin); 00465 stream.next(m.angle_end); 00466 stream.next(m.duration); 00467 } 00468 00469 ROS_DECLARE_ALLINONE_SERIALIZER; 00470 }; // struct BuildCloudAngleRequest_ 00471 } // namespace serialization 00472 } // namespace ros 00473 00474 00475 namespace ros 00476 { 00477 namespace serialization 00478 { 00479 00480 template<class ContainerAllocator> struct Serializer< ::pr2_arm_navigation_perception::BuildCloudAngleResponse_<ContainerAllocator> > 00481 { 00482 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00483 { 00484 stream.next(m.cloud); 00485 } 00486 00487 ROS_DECLARE_ALLINONE_SERIALIZER; 00488 }; // struct BuildCloudAngleResponse_ 00489 } // namespace serialization 00490 } // namespace ros 00491 00492 namespace ros 00493 { 00494 namespace service_traits 00495 { 00496 template<> 00497 struct MD5Sum<pr2_arm_navigation_perception::BuildCloudAngle> { 00498 static const char* value() 00499 { 00500 return "7469d22e99d2e7f342cec297b7bb49d3"; 00501 } 00502 00503 static const char* value(const pr2_arm_navigation_perception::BuildCloudAngle&) { return value(); } 00504 }; 00505 00506 template<> 00507 struct DataType<pr2_arm_navigation_perception::BuildCloudAngle> { 00508 static const char* value() 00509 { 00510 return "pr2_arm_navigation_perception/BuildCloudAngle"; 00511 } 00512 00513 static const char* value(const pr2_arm_navigation_perception::BuildCloudAngle&) { return value(); } 00514 }; 00515 00516 template<class ContainerAllocator> 00517 struct MD5Sum<pr2_arm_navigation_perception::BuildCloudAngleRequest_<ContainerAllocator> > { 00518 static const char* value() 00519 { 00520 return "7469d22e99d2e7f342cec297b7bb49d3"; 00521 } 00522 00523 static const char* value(const pr2_arm_navigation_perception::BuildCloudAngleRequest_<ContainerAllocator> &) { return value(); } 00524 }; 00525 00526 template<class ContainerAllocator> 00527 struct DataType<pr2_arm_navigation_perception::BuildCloudAngleRequest_<ContainerAllocator> > { 00528 static const char* value() 00529 { 00530 return "pr2_arm_navigation_perception/BuildCloudAngle"; 00531 } 00532 00533 static const char* value(const pr2_arm_navigation_perception::BuildCloudAngleRequest_<ContainerAllocator> &) { return value(); } 00534 }; 00535 00536 template<class ContainerAllocator> 00537 struct MD5Sum<pr2_arm_navigation_perception::BuildCloudAngleResponse_<ContainerAllocator> > { 00538 static const char* value() 00539 { 00540 return "7469d22e99d2e7f342cec297b7bb49d3"; 00541 } 00542 00543 static const char* value(const pr2_arm_navigation_perception::BuildCloudAngleResponse_<ContainerAllocator> &) { return value(); } 00544 }; 00545 00546 template<class ContainerAllocator> 00547 struct DataType<pr2_arm_navigation_perception::BuildCloudAngleResponse_<ContainerAllocator> > { 00548 static const char* value() 00549 { 00550 return "pr2_arm_navigation_perception/BuildCloudAngle"; 00551 } 00552 00553 static const char* value(const pr2_arm_navigation_perception::BuildCloudAngleResponse_<ContainerAllocator> &) { return value(); } 00554 }; 00555 00556 } // namespace service_traits 00557 } // namespace ros 00558 00559 #endif // PR2_ARM_NAVIGATION_PERCEPTION_SERVICE_BUILDCLOUDANGLE_H 00560