00001
00002 #ifndef DOOR_HANDLE_DETECTOR_SERVICE_DOORSDETECTORCLOUD_H
00003 #define DOOR_HANDLE_DETECTOR_SERVICE_DOORSDETECTORCLOUD_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 "door_msgs/Door.h"
00016 #include "sensor_msgs/PointCloud.h"
00017
00018
00019 #include "door_msgs/Door.h"
00020
00021 namespace door_handle_detector
00022 {
00023 template <class ContainerAllocator>
00024 struct DoorsDetectorCloudRequest_ : public ros::Message
00025 {
00026 typedef DoorsDetectorCloudRequest_<ContainerAllocator> Type;
00027
00028 DoorsDetectorCloudRequest_()
00029 : door()
00030 , cloud()
00031 {
00032 }
00033
00034 DoorsDetectorCloudRequest_(const ContainerAllocator& _alloc)
00035 : door(_alloc)
00036 , cloud(_alloc)
00037 {
00038 }
00039
00040 typedef ::door_msgs::Door_<ContainerAllocator> _door_type;
00041 ::door_msgs::Door_<ContainerAllocator> door;
00042
00043 typedef ::sensor_msgs::PointCloud_<ContainerAllocator> _cloud_type;
00044 ::sensor_msgs::PointCloud_<ContainerAllocator> cloud;
00045
00046
00047 private:
00048 static const char* __s_getDataType_() { return "door_handle_detector/DoorsDetectorCloudRequest"; }
00049 public:
00050 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00051
00052 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00053
00054 private:
00055 static const char* __s_getMD5Sum_() { return "46b5580ee042093a9a5254367bb8a4ee"; }
00056 public:
00057 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00058
00059 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00060
00061 private:
00062 static const char* __s_getServerMD5Sum_() { return "0dadc6e3af89de943ea049368f297d58"; }
00063 public:
00064 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00065
00066 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00067
00068 private:
00069 static const char* __s_getMessageDefinition_() { return "door_msgs/Door door\n\
00070 sensor_msgs/PointCloud cloud\n\
00071 \n\
00072 ================================================================================\n\
00073 MSG: door_msgs/Door\n\
00074 Header header\n\
00075 geometry_msgs/Point32 frame_p1 ## position of the door frame\n\
00076 geometry_msgs/Point32 frame_p2 ## position of the door frame\n\
00077 geometry_msgs/Point32 door_p1 ## Ground plane projection of a point on the plane of the door \n\
00078 geometry_msgs/Point32 door_p2 ## Ground plane projection of a point on the plane of the door\n\
00079 geometry_msgs/Point32 handle ## Position of the door handle\n\
00080 float32 height ## Height of the door\n\
00081 \n\
00082 int32 UNKNOWN=0\n\
00083 \n\
00084 int32 HINGE_P1=1\n\
00085 int32 HINGE_P2=2\n\
00086 int32 hinge \n\
00087 \n\
00088 int32 ROT_DIR_CLOCKWISE=1\n\
00089 int32 ROT_DIR_COUNTERCLOCKWISE=2\n\
00090 int32 rot_dir \n\
00091 \n\
00092 int32 LOCKED=1\n\
00093 int32 LATCHED=2\n\
00094 int32 UNLATCHED=3\n\
00095 int32 latch_state \n\
00096 \n\
00097 geometry_msgs/Vector3 travel_dir ## vector pointing in the direction the robot is going to travel through the door\n\
00098 float32 weight ## @Sachin: what do we use this for?\n\
00099 \n\
00100 \n\
00101 \n\
00102 ================================================================================\n\
00103 MSG: std_msgs/Header\n\
00104 # Standard metadata for higher-level stamped data types.\n\
00105 # This is generally used to communicate timestamped data \n\
00106 # in a particular coordinate frame.\n\
00107 # \n\
00108 # sequence ID: consecutively increasing ID \n\
00109 uint32 seq\n\
00110 #Two-integer timestamp that is expressed as:\n\
00111 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00112 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00113 # time-handling sugar is provided by the client library\n\
00114 time stamp\n\
00115 #Frame this data is associated with\n\
00116 # 0: no frame\n\
00117 # 1: global frame\n\
00118 string frame_id\n\
00119 \n\
00120 ================================================================================\n\
00121 MSG: geometry_msgs/Point32\n\
00122 # This contains the position of a point in free space(with 32 bits of precision).\n\
00123 # It is recommeded to use Point wherever possible instead of Point32. \n\
00124 # \n\
00125 # This recommendation is to promote interoperability. \n\
00126 #\n\
00127 # This message is designed to take up less space when sending\n\
00128 # lots of points at once, as in the case of a PointCloud. \n\
00129 \n\
00130 float32 x\n\
00131 float32 y\n\
00132 float32 z\n\
00133 ================================================================================\n\
00134 MSG: geometry_msgs/Vector3\n\
00135 # This represents a vector in free space. \n\
00136 \n\
00137 float64 x\n\
00138 float64 y\n\
00139 float64 z\n\
00140 ================================================================================\n\
00141 MSG: sensor_msgs/PointCloud\n\
00142 # This message holds a collection of 3d points, plus optional additional\n\
00143 # information about each point.\n\
00144 \n\
00145 # Time of sensor data acquisition, coordinate frame ID.\n\
00146 Header header\n\
00147 \n\
00148 # Array of 3d points. Each Point32 should be interpreted as a 3d point\n\
00149 # in the frame given in the header.\n\
00150 geometry_msgs/Point32[] points\n\
00151 \n\
00152 # Each channel should have the same number of elements as points array,\n\
00153 # and the data in each channel should correspond 1:1 with each point.\n\
00154 # Channel names in common practice are listed in ChannelFloat32.msg.\n\
00155 ChannelFloat32[] channels\n\
00156 \n\
00157 ================================================================================\n\
00158 MSG: sensor_msgs/ChannelFloat32\n\
00159 # This message is used by the PointCloud message to hold optional data\n\
00160 # associated with each point in the cloud. The length of the values\n\
00161 # array should be the same as the length of the points array in the\n\
00162 # PointCloud, and each value should be associated with the corresponding\n\
00163 # point.\n\
00164 \n\
00165 # Channel names in existing practice include:\n\
00166 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\
00167 # This is opposite to usual conventions but remains for\n\
00168 # historical reasons. The newer PointCloud2 message has no\n\
00169 # such problem.\n\
00170 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\
00171 # (R,G,B) values packed into the least significant 24 bits,\n\
00172 # in order.\n\
00173 # \"intensity\" - laser or pixel intensity.\n\
00174 # \"distance\"\n\
00175 \n\
00176 # The channel name should give semantics of the channel (e.g.\n\
00177 # \"intensity\" instead of \"value\").\n\
00178 string name\n\
00179 \n\
00180 # The values array should be 1-1 with the elements of the associated\n\
00181 # PointCloud.\n\
00182 float32[] values\n\
00183 \n\
00184 "; }
00185 public:
00186 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00187
00188 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00189
00190 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00191 {
00192 ros::serialization::OStream stream(write_ptr, 1000000000);
00193 ros::serialization::serialize(stream, door);
00194 ros::serialization::serialize(stream, cloud);
00195 return stream.getData();
00196 }
00197
00198 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00199 {
00200 ros::serialization::IStream stream(read_ptr, 1000000000);
00201 ros::serialization::deserialize(stream, door);
00202 ros::serialization::deserialize(stream, cloud);
00203 return stream.getData();
00204 }
00205
00206 ROS_DEPRECATED virtual uint32_t serializationLength() const
00207 {
00208 uint32_t size = 0;
00209 size += ros::serialization::serializationLength(door);
00210 size += ros::serialization::serializationLength(cloud);
00211 return size;
00212 }
00213
00214 typedef boost::shared_ptr< ::door_handle_detector::DoorsDetectorCloudRequest_<ContainerAllocator> > Ptr;
00215 typedef boost::shared_ptr< ::door_handle_detector::DoorsDetectorCloudRequest_<ContainerAllocator> const> ConstPtr;
00216 };
00217 typedef ::door_handle_detector::DoorsDetectorCloudRequest_<std::allocator<void> > DoorsDetectorCloudRequest;
00218
00219 typedef boost::shared_ptr< ::door_handle_detector::DoorsDetectorCloudRequest> DoorsDetectorCloudRequestPtr;
00220 typedef boost::shared_ptr< ::door_handle_detector::DoorsDetectorCloudRequest const> DoorsDetectorCloudRequestConstPtr;
00221
00222
00223 template <class ContainerAllocator>
00224 struct DoorsDetectorCloudResponse_ : public ros::Message
00225 {
00226 typedef DoorsDetectorCloudResponse_<ContainerAllocator> Type;
00227
00228 DoorsDetectorCloudResponse_()
00229 : doors()
00230 {
00231 }
00232
00233 DoorsDetectorCloudResponse_(const ContainerAllocator& _alloc)
00234 : doors(_alloc)
00235 {
00236 }
00237
00238 typedef std::vector< ::door_msgs::Door_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::door_msgs::Door_<ContainerAllocator> >::other > _doors_type;
00239 std::vector< ::door_msgs::Door_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::door_msgs::Door_<ContainerAllocator> >::other > doors;
00240
00241
00242 ROS_DEPRECATED uint32_t get_doors_size() const { return (uint32_t)doors.size(); }
00243 ROS_DEPRECATED void set_doors_size(uint32_t size) { doors.resize((size_t)size); }
00244 ROS_DEPRECATED void get_doors_vec(std::vector< ::door_msgs::Door_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::door_msgs::Door_<ContainerAllocator> >::other > & vec) const { vec = this->doors; }
00245 ROS_DEPRECATED void set_doors_vec(const std::vector< ::door_msgs::Door_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::door_msgs::Door_<ContainerAllocator> >::other > & vec) { this->doors = vec; }
00246 private:
00247 static const char* __s_getDataType_() { return "door_handle_detector/DoorsDetectorCloudResponse"; }
00248 public:
00249 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00250
00251 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00252
00253 private:
00254 static const char* __s_getMD5Sum_() { return "814c1a77e8c0b7c5b3832dabceff607d"; }
00255 public:
00256 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00257
00258 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00259
00260 private:
00261 static const char* __s_getServerMD5Sum_() { return "0dadc6e3af89de943ea049368f297d58"; }
00262 public:
00263 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00264
00265 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00266
00267 private:
00268 static const char* __s_getMessageDefinition_() { return "door_msgs/Door[] doors\n\
00269 \n\
00270 \n\
00271 ================================================================================\n\
00272 MSG: door_msgs/Door\n\
00273 Header header\n\
00274 geometry_msgs/Point32 frame_p1 ## position of the door frame\n\
00275 geometry_msgs/Point32 frame_p2 ## position of the door frame\n\
00276 geometry_msgs/Point32 door_p1 ## Ground plane projection of a point on the plane of the door \n\
00277 geometry_msgs/Point32 door_p2 ## Ground plane projection of a point on the plane of the door\n\
00278 geometry_msgs/Point32 handle ## Position of the door handle\n\
00279 float32 height ## Height of the door\n\
00280 \n\
00281 int32 UNKNOWN=0\n\
00282 \n\
00283 int32 HINGE_P1=1\n\
00284 int32 HINGE_P2=2\n\
00285 int32 hinge \n\
00286 \n\
00287 int32 ROT_DIR_CLOCKWISE=1\n\
00288 int32 ROT_DIR_COUNTERCLOCKWISE=2\n\
00289 int32 rot_dir \n\
00290 \n\
00291 int32 LOCKED=1\n\
00292 int32 LATCHED=2\n\
00293 int32 UNLATCHED=3\n\
00294 int32 latch_state \n\
00295 \n\
00296 geometry_msgs/Vector3 travel_dir ## vector pointing in the direction the robot is going to travel through the door\n\
00297 float32 weight ## @Sachin: what do we use this for?\n\
00298 \n\
00299 \n\
00300 \n\
00301 ================================================================================\n\
00302 MSG: std_msgs/Header\n\
00303 # Standard metadata for higher-level stamped data types.\n\
00304 # This is generally used to communicate timestamped data \n\
00305 # in a particular coordinate frame.\n\
00306 # \n\
00307 # sequence ID: consecutively increasing ID \n\
00308 uint32 seq\n\
00309 #Two-integer timestamp that is expressed as:\n\
00310 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00311 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00312 # time-handling sugar is provided by the client library\n\
00313 time stamp\n\
00314 #Frame this data is associated with\n\
00315 # 0: no frame\n\
00316 # 1: global frame\n\
00317 string frame_id\n\
00318 \n\
00319 ================================================================================\n\
00320 MSG: geometry_msgs/Point32\n\
00321 # This contains the position of a point in free space(with 32 bits of precision).\n\
00322 # It is recommeded to use Point wherever possible instead of Point32. \n\
00323 # \n\
00324 # This recommendation is to promote interoperability. \n\
00325 #\n\
00326 # This message is designed to take up less space when sending\n\
00327 # lots of points at once, as in the case of a PointCloud. \n\
00328 \n\
00329 float32 x\n\
00330 float32 y\n\
00331 float32 z\n\
00332 ================================================================================\n\
00333 MSG: geometry_msgs/Vector3\n\
00334 # This represents a vector in free space. \n\
00335 \n\
00336 float64 x\n\
00337 float64 y\n\
00338 float64 z\n\
00339 "; }
00340 public:
00341 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00342
00343 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00344
00345 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00346 {
00347 ros::serialization::OStream stream(write_ptr, 1000000000);
00348 ros::serialization::serialize(stream, doors);
00349 return stream.getData();
00350 }
00351
00352 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00353 {
00354 ros::serialization::IStream stream(read_ptr, 1000000000);
00355 ros::serialization::deserialize(stream, doors);
00356 return stream.getData();
00357 }
00358
00359 ROS_DEPRECATED virtual uint32_t serializationLength() const
00360 {
00361 uint32_t size = 0;
00362 size += ros::serialization::serializationLength(doors);
00363 return size;
00364 }
00365
00366 typedef boost::shared_ptr< ::door_handle_detector::DoorsDetectorCloudResponse_<ContainerAllocator> > Ptr;
00367 typedef boost::shared_ptr< ::door_handle_detector::DoorsDetectorCloudResponse_<ContainerAllocator> const> ConstPtr;
00368 };
00369 typedef ::door_handle_detector::DoorsDetectorCloudResponse_<std::allocator<void> > DoorsDetectorCloudResponse;
00370
00371 typedef boost::shared_ptr< ::door_handle_detector::DoorsDetectorCloudResponse> DoorsDetectorCloudResponsePtr;
00372 typedef boost::shared_ptr< ::door_handle_detector::DoorsDetectorCloudResponse const> DoorsDetectorCloudResponseConstPtr;
00373
00374 struct DoorsDetectorCloud
00375 {
00376
00377 typedef DoorsDetectorCloudRequest Request;
00378 typedef DoorsDetectorCloudResponse Response;
00379 Request request;
00380 Response response;
00381
00382 typedef Request RequestType;
00383 typedef Response ResponseType;
00384 };
00385 }
00386
00387 namespace ros
00388 {
00389 namespace message_traits
00390 {
00391 template<class ContainerAllocator>
00392 struct MD5Sum< ::door_handle_detector::DoorsDetectorCloudRequest_<ContainerAllocator> > {
00393 static const char* value()
00394 {
00395 return "46b5580ee042093a9a5254367bb8a4ee";
00396 }
00397
00398 static const char* value(const ::door_handle_detector::DoorsDetectorCloudRequest_<ContainerAllocator> &) { return value(); }
00399 static const uint64_t static_value1 = 0x46b5580ee042093aULL;
00400 static const uint64_t static_value2 = 0x9a5254367bb8a4eeULL;
00401 };
00402
00403 template<class ContainerAllocator>
00404 struct DataType< ::door_handle_detector::DoorsDetectorCloudRequest_<ContainerAllocator> > {
00405 static const char* value()
00406 {
00407 return "door_handle_detector/DoorsDetectorCloudRequest";
00408 }
00409
00410 static const char* value(const ::door_handle_detector::DoorsDetectorCloudRequest_<ContainerAllocator> &) { return value(); }
00411 };
00412
00413 template<class ContainerAllocator>
00414 struct Definition< ::door_handle_detector::DoorsDetectorCloudRequest_<ContainerAllocator> > {
00415 static const char* value()
00416 {
00417 return "door_msgs/Door door\n\
00418 sensor_msgs/PointCloud cloud\n\
00419 \n\
00420 ================================================================================\n\
00421 MSG: door_msgs/Door\n\
00422 Header header\n\
00423 geometry_msgs/Point32 frame_p1 ## position of the door frame\n\
00424 geometry_msgs/Point32 frame_p2 ## position of the door frame\n\
00425 geometry_msgs/Point32 door_p1 ## Ground plane projection of a point on the plane of the door \n\
00426 geometry_msgs/Point32 door_p2 ## Ground plane projection of a point on the plane of the door\n\
00427 geometry_msgs/Point32 handle ## Position of the door handle\n\
00428 float32 height ## Height of the door\n\
00429 \n\
00430 int32 UNKNOWN=0\n\
00431 \n\
00432 int32 HINGE_P1=1\n\
00433 int32 HINGE_P2=2\n\
00434 int32 hinge \n\
00435 \n\
00436 int32 ROT_DIR_CLOCKWISE=1\n\
00437 int32 ROT_DIR_COUNTERCLOCKWISE=2\n\
00438 int32 rot_dir \n\
00439 \n\
00440 int32 LOCKED=1\n\
00441 int32 LATCHED=2\n\
00442 int32 UNLATCHED=3\n\
00443 int32 latch_state \n\
00444 \n\
00445 geometry_msgs/Vector3 travel_dir ## vector pointing in the direction the robot is going to travel through the door\n\
00446 float32 weight ## @Sachin: what do we use this for?\n\
00447 \n\
00448 \n\
00449 \n\
00450 ================================================================================\n\
00451 MSG: std_msgs/Header\n\
00452 # Standard metadata for higher-level stamped data types.\n\
00453 # This is generally used to communicate timestamped data \n\
00454 # in a particular coordinate frame.\n\
00455 # \n\
00456 # sequence ID: consecutively increasing ID \n\
00457 uint32 seq\n\
00458 #Two-integer timestamp that is expressed as:\n\
00459 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00460 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00461 # time-handling sugar is provided by the client library\n\
00462 time stamp\n\
00463 #Frame this data is associated with\n\
00464 # 0: no frame\n\
00465 # 1: global frame\n\
00466 string frame_id\n\
00467 \n\
00468 ================================================================================\n\
00469 MSG: geometry_msgs/Point32\n\
00470 # This contains the position of a point in free space(with 32 bits of precision).\n\
00471 # It is recommeded to use Point wherever possible instead of Point32. \n\
00472 # \n\
00473 # This recommendation is to promote interoperability. \n\
00474 #\n\
00475 # This message is designed to take up less space when sending\n\
00476 # lots of points at once, as in the case of a PointCloud. \n\
00477 \n\
00478 float32 x\n\
00479 float32 y\n\
00480 float32 z\n\
00481 ================================================================================\n\
00482 MSG: geometry_msgs/Vector3\n\
00483 # This represents a vector in free space. \n\
00484 \n\
00485 float64 x\n\
00486 float64 y\n\
00487 float64 z\n\
00488 ================================================================================\n\
00489 MSG: sensor_msgs/PointCloud\n\
00490 # This message holds a collection of 3d points, plus optional additional\n\
00491 # information about each point.\n\
00492 \n\
00493 # Time of sensor data acquisition, coordinate frame ID.\n\
00494 Header header\n\
00495 \n\
00496 # Array of 3d points. Each Point32 should be interpreted as a 3d point\n\
00497 # in the frame given in the header.\n\
00498 geometry_msgs/Point32[] points\n\
00499 \n\
00500 # Each channel should have the same number of elements as points array,\n\
00501 # and the data in each channel should correspond 1:1 with each point.\n\
00502 # Channel names in common practice are listed in ChannelFloat32.msg.\n\
00503 ChannelFloat32[] channels\n\
00504 \n\
00505 ================================================================================\n\
00506 MSG: sensor_msgs/ChannelFloat32\n\
00507 # This message is used by the PointCloud message to hold optional data\n\
00508 # associated with each point in the cloud. The length of the values\n\
00509 # array should be the same as the length of the points array in the\n\
00510 # PointCloud, and each value should be associated with the corresponding\n\
00511 # point.\n\
00512 \n\
00513 # Channel names in existing practice include:\n\
00514 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\
00515 # This is opposite to usual conventions but remains for\n\
00516 # historical reasons. The newer PointCloud2 message has no\n\
00517 # such problem.\n\
00518 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\
00519 # (R,G,B) values packed into the least significant 24 bits,\n\
00520 # in order.\n\
00521 # \"intensity\" - laser or pixel intensity.\n\
00522 # \"distance\"\n\
00523 \n\
00524 # The channel name should give semantics of the channel (e.g.\n\
00525 # \"intensity\" instead of \"value\").\n\
00526 string name\n\
00527 \n\
00528 # The values array should be 1-1 with the elements of the associated\n\
00529 # PointCloud.\n\
00530 float32[] values\n\
00531 \n\
00532 ";
00533 }
00534
00535 static const char* value(const ::door_handle_detector::DoorsDetectorCloudRequest_<ContainerAllocator> &) { return value(); }
00536 };
00537
00538 }
00539 }
00540
00541
00542 namespace ros
00543 {
00544 namespace message_traits
00545 {
00546 template<class ContainerAllocator>
00547 struct MD5Sum< ::door_handle_detector::DoorsDetectorCloudResponse_<ContainerAllocator> > {
00548 static const char* value()
00549 {
00550 return "814c1a77e8c0b7c5b3832dabceff607d";
00551 }
00552
00553 static const char* value(const ::door_handle_detector::DoorsDetectorCloudResponse_<ContainerAllocator> &) { return value(); }
00554 static const uint64_t static_value1 = 0x814c1a77e8c0b7c5ULL;
00555 static const uint64_t static_value2 = 0xb3832dabceff607dULL;
00556 };
00557
00558 template<class ContainerAllocator>
00559 struct DataType< ::door_handle_detector::DoorsDetectorCloudResponse_<ContainerAllocator> > {
00560 static const char* value()
00561 {
00562 return "door_handle_detector/DoorsDetectorCloudResponse";
00563 }
00564
00565 static const char* value(const ::door_handle_detector::DoorsDetectorCloudResponse_<ContainerAllocator> &) { return value(); }
00566 };
00567
00568 template<class ContainerAllocator>
00569 struct Definition< ::door_handle_detector::DoorsDetectorCloudResponse_<ContainerAllocator> > {
00570 static const char* value()
00571 {
00572 return "door_msgs/Door[] doors\n\
00573 \n\
00574 \n\
00575 ================================================================================\n\
00576 MSG: door_msgs/Door\n\
00577 Header header\n\
00578 geometry_msgs/Point32 frame_p1 ## position of the door frame\n\
00579 geometry_msgs/Point32 frame_p2 ## position of the door frame\n\
00580 geometry_msgs/Point32 door_p1 ## Ground plane projection of a point on the plane of the door \n\
00581 geometry_msgs/Point32 door_p2 ## Ground plane projection of a point on the plane of the door\n\
00582 geometry_msgs/Point32 handle ## Position of the door handle\n\
00583 float32 height ## Height of the door\n\
00584 \n\
00585 int32 UNKNOWN=0\n\
00586 \n\
00587 int32 HINGE_P1=1\n\
00588 int32 HINGE_P2=2\n\
00589 int32 hinge \n\
00590 \n\
00591 int32 ROT_DIR_CLOCKWISE=1\n\
00592 int32 ROT_DIR_COUNTERCLOCKWISE=2\n\
00593 int32 rot_dir \n\
00594 \n\
00595 int32 LOCKED=1\n\
00596 int32 LATCHED=2\n\
00597 int32 UNLATCHED=3\n\
00598 int32 latch_state \n\
00599 \n\
00600 geometry_msgs/Vector3 travel_dir ## vector pointing in the direction the robot is going to travel through the door\n\
00601 float32 weight ## @Sachin: what do we use this for?\n\
00602 \n\
00603 \n\
00604 \n\
00605 ================================================================================\n\
00606 MSG: std_msgs/Header\n\
00607 # Standard metadata for higher-level stamped data types.\n\
00608 # This is generally used to communicate timestamped data \n\
00609 # in a particular coordinate frame.\n\
00610 # \n\
00611 # sequence ID: consecutively increasing ID \n\
00612 uint32 seq\n\
00613 #Two-integer timestamp that is expressed as:\n\
00614 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00615 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00616 # time-handling sugar is provided by the client library\n\
00617 time stamp\n\
00618 #Frame this data is associated with\n\
00619 # 0: no frame\n\
00620 # 1: global frame\n\
00621 string frame_id\n\
00622 \n\
00623 ================================================================================\n\
00624 MSG: geometry_msgs/Point32\n\
00625 # This contains the position of a point in free space(with 32 bits of precision).\n\
00626 # It is recommeded to use Point wherever possible instead of Point32. \n\
00627 # \n\
00628 # This recommendation is to promote interoperability. \n\
00629 #\n\
00630 # This message is designed to take up less space when sending\n\
00631 # lots of points at once, as in the case of a PointCloud. \n\
00632 \n\
00633 float32 x\n\
00634 float32 y\n\
00635 float32 z\n\
00636 ================================================================================\n\
00637 MSG: geometry_msgs/Vector3\n\
00638 # This represents a vector in free space. \n\
00639 \n\
00640 float64 x\n\
00641 float64 y\n\
00642 float64 z\n\
00643 ";
00644 }
00645
00646 static const char* value(const ::door_handle_detector::DoorsDetectorCloudResponse_<ContainerAllocator> &) { return value(); }
00647 };
00648
00649 }
00650 }
00651
00652 namespace ros
00653 {
00654 namespace serialization
00655 {
00656
00657 template<class ContainerAllocator> struct Serializer< ::door_handle_detector::DoorsDetectorCloudRequest_<ContainerAllocator> >
00658 {
00659 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00660 {
00661 stream.next(m.door);
00662 stream.next(m.cloud);
00663 }
00664
00665 ROS_DECLARE_ALLINONE_SERIALIZER;
00666 };
00667 }
00668 }
00669
00670
00671 namespace ros
00672 {
00673 namespace serialization
00674 {
00675
00676 template<class ContainerAllocator> struct Serializer< ::door_handle_detector::DoorsDetectorCloudResponse_<ContainerAllocator> >
00677 {
00678 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00679 {
00680 stream.next(m.doors);
00681 }
00682
00683 ROS_DECLARE_ALLINONE_SERIALIZER;
00684 };
00685 }
00686 }
00687
00688 namespace ros
00689 {
00690 namespace service_traits
00691 {
00692 template<>
00693 struct MD5Sum<door_handle_detector::DoorsDetectorCloud> {
00694 static const char* value()
00695 {
00696 return "0dadc6e3af89de943ea049368f297d58";
00697 }
00698
00699 static const char* value(const door_handle_detector::DoorsDetectorCloud&) { return value(); }
00700 };
00701
00702 template<>
00703 struct DataType<door_handle_detector::DoorsDetectorCloud> {
00704 static const char* value()
00705 {
00706 return "door_handle_detector/DoorsDetectorCloud";
00707 }
00708
00709 static const char* value(const door_handle_detector::DoorsDetectorCloud&) { return value(); }
00710 };
00711
00712 template<class ContainerAllocator>
00713 struct MD5Sum<door_handle_detector::DoorsDetectorCloudRequest_<ContainerAllocator> > {
00714 static const char* value()
00715 {
00716 return "0dadc6e3af89de943ea049368f297d58";
00717 }
00718
00719 static const char* value(const door_handle_detector::DoorsDetectorCloudRequest_<ContainerAllocator> &) { return value(); }
00720 };
00721
00722 template<class ContainerAllocator>
00723 struct DataType<door_handle_detector::DoorsDetectorCloudRequest_<ContainerAllocator> > {
00724 static const char* value()
00725 {
00726 return "door_handle_detector/DoorsDetectorCloud";
00727 }
00728
00729 static const char* value(const door_handle_detector::DoorsDetectorCloudRequest_<ContainerAllocator> &) { return value(); }
00730 };
00731
00732 template<class ContainerAllocator>
00733 struct MD5Sum<door_handle_detector::DoorsDetectorCloudResponse_<ContainerAllocator> > {
00734 static const char* value()
00735 {
00736 return "0dadc6e3af89de943ea049368f297d58";
00737 }
00738
00739 static const char* value(const door_handle_detector::DoorsDetectorCloudResponse_<ContainerAllocator> &) { return value(); }
00740 };
00741
00742 template<class ContainerAllocator>
00743 struct DataType<door_handle_detector::DoorsDetectorCloudResponse_<ContainerAllocator> > {
00744 static const char* value()
00745 {
00746 return "door_handle_detector/DoorsDetectorCloud";
00747 }
00748
00749 static const char* value(const door_handle_detector::DoorsDetectorCloudResponse_<ContainerAllocator> &) { return value(); }
00750 };
00751
00752 }
00753 }
00754
00755 #endif // DOOR_HANDLE_DETECTOR_SERVICE_DOORSDETECTORCLOUD_H
00756