$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-vision_visp/doc_stacks/2013-03-02_14-13-07.148743/vision_visp/visp_tracker/srv/Init.srv */ 00002 #ifndef VISP_TRACKER_SERVICE_INIT_H 00003 #define VISP_TRACKER_SERVICE_INIT_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 #include "geometry_msgs/Transform.h" 00020 #include "visp_tracker/MovingEdge.h" 00021 00022 00023 00024 namespace visp_tracker 00025 { 00026 template <class ContainerAllocator> 00027 struct InitRequest_ { 00028 typedef InitRequest_<ContainerAllocator> Type; 00029 00030 InitRequest_() 00031 : initial_cMo() 00032 , moving_edge() 00033 { 00034 } 00035 00036 InitRequest_(const ContainerAllocator& _alloc) 00037 : initial_cMo(_alloc) 00038 , moving_edge(_alloc) 00039 { 00040 } 00041 00042 typedef ::geometry_msgs::Transform_<ContainerAllocator> _initial_cMo_type; 00043 ::geometry_msgs::Transform_<ContainerAllocator> initial_cMo; 00044 00045 typedef ::visp_tracker::MovingEdge_<ContainerAllocator> _moving_edge_type; 00046 ::visp_tracker::MovingEdge_<ContainerAllocator> moving_edge; 00047 00048 00049 private: 00050 static const char* __s_getDataType_() { return "visp_tracker/InitRequest"; } 00051 public: 00052 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00053 00054 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00055 00056 private: 00057 static const char* __s_getMD5Sum_() { return "440a9fdc3875f06ac1d9d7ab02a58456"; } 00058 public: 00059 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00060 00061 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00062 00063 private: 00064 static const char* __s_getServerMD5Sum_() { return "d9f7c7c2435e9d0af6283a1aac362aac"; } 00065 public: 00066 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00067 00068 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00069 00070 private: 00071 static const char* __s_getMessageDefinition_() { return "\n\ 00072 \n\ 00073 \n\ 00074 \n\ 00075 \n\ 00076 \n\ 00077 \n\ 00078 \n\ 00079 \n\ 00080 geometry_msgs/Transform initial_cMo\n\ 00081 \n\ 00082 \n\ 00083 MovingEdge moving_edge\n\ 00084 \n\ 00085 ================================================================================\n\ 00086 MSG: geometry_msgs/Transform\n\ 00087 # This represents the transform between two coordinate frames in free space.\n\ 00088 \n\ 00089 Vector3 translation\n\ 00090 Quaternion rotation\n\ 00091 \n\ 00092 ================================================================================\n\ 00093 MSG: geometry_msgs/Vector3\n\ 00094 # This represents a vector in free space. \n\ 00095 \n\ 00096 float64 x\n\ 00097 float64 y\n\ 00098 float64 z\n\ 00099 ================================================================================\n\ 00100 MSG: geometry_msgs/Quaternion\n\ 00101 # This represents an orientation in free space in quaternion form.\n\ 00102 \n\ 00103 float64 x\n\ 00104 float64 y\n\ 00105 float64 z\n\ 00106 float64 w\n\ 00107 \n\ 00108 ================================================================================\n\ 00109 MSG: visp_tracker/MovingEdge\n\ 00110 # This message contains tracking parameters.\n\ 00111 #\n\ 00112 # These parameters determine how precise, how fast and how\n\ 00113 # reliable will be the tracking.\n\ 00114 #\n\ 00115 # It should be tuned carefully and can be changed dynamically.\n\ 00116 #\n\ 00117 # For more details, see the ViSP documentation:\n\ 00118 # http://www.irisa.fr/lagadic/visp/publication.html\n\ 00119 \n\ 00120 \n\ 00121 # Moving edge parameters.\n\ 00122 \n\ 00123 int64 mask_size # Mask size (in pixel) used to compute the image gradient\n\ 00124 # and determine the object contour.\n\ 00125 # A larger mask size is better for larger images.\n\ 00126 # 3 pixels is enough for 640x480 images.\n\ 00127 # Increasing this value makes the tracking slower.\n\ 00128 #\n\ 00129 # Caution: this value cannot be changed dynamically\n\ 00130 # without resetting the tracking.\n\ 00131 \n\ 00132 int64 n_mask # Number of masks applied to determine the object contour.\n\ 00133 # Increasing this value makes the tracking slower.\n\ 00134 \n\ 00135 int64 range # Maximum seek distance on both sides of the reference pixel.\n\ 00136 # It should match the maximum distance in pixel between\n\ 00137 # the current position of the feature projection and\n\ 00138 # its next position.\n\ 00139 # I.e. if the object moves fast and your tracking\n\ 00140 # frequency is low, this value should be increased.\n\ 00141 # Increasing this value makes the tracking slower.\n\ 00142 \n\ 00143 float64 threshold # Value used to determine if a moving edge is valid\n\ 00144 # or not.\n\ 00145 \n\ 00146 float64 mu1 # Minimum image contrast allowed to detect a contour.\n\ 00147 float64 mu2 # Maximum image contrast allowed to detect a contour.\n\ 00148 \n\ 00149 int64 sample_step # Minimum distance in pixel between two\n\ 00150 # discretization points.\n\ 00151 # It avoids having too many discretization points when\n\ 00152 # the tracked object is far away (and its projection\n\ 00153 # in the image is small).\n\ 00154 # Increasing this value makes the tracking *faster*.\n\ 00155 \n\ 00156 int64 ntotal_sample # How many discretization points are used to track the\n\ 00157 # feature.\n\ 00158 # Higher is better but slow down the tracking.\n\ 00159 # The best value depends on your model and its distance\n\ 00160 # with respect to the camera.\n\ 00161 # Increasing this value makes the tracking slower.\n\ 00162 \n\ 00163 int64 strip # How many pixels are ignored around the borders.\n\ 00164 float64 min_samplestep # Minimum allowed samplestep. Useful to specify\n\ 00165 # a lower bound when the samplestep is changed\n\ 00166 # dynamically.\n\ 00167 # This is not done by visp_tracker currently.\n\ 00168 float64 aberration # Ignored.\n\ 00169 float64 init_aberration # Ignored.\n\ 00170 \n\ 00171 \n\ 00172 # Tracker parameters.\n\ 00173 \n\ 00174 float64 lambda # Gain used to compute the control law.\n\ 00175 float64 first_threshold # What proportion of points should be valid to\n\ 00176 # acccept an initial pose.\n\ 00177 # Value should be between 0 et 1.\n\ 00178 \n\ 00179 "; } 00180 public: 00181 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00182 00183 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00184 00185 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00186 { 00187 ros::serialization::OStream stream(write_ptr, 1000000000); 00188 ros::serialization::serialize(stream, initial_cMo); 00189 ros::serialization::serialize(stream, moving_edge); 00190 return stream.getData(); 00191 } 00192 00193 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00194 { 00195 ros::serialization::IStream stream(read_ptr, 1000000000); 00196 ros::serialization::deserialize(stream, initial_cMo); 00197 ros::serialization::deserialize(stream, moving_edge); 00198 return stream.getData(); 00199 } 00200 00201 ROS_DEPRECATED virtual uint32_t serializationLength() const 00202 { 00203 uint32_t size = 0; 00204 size += ros::serialization::serializationLength(initial_cMo); 00205 size += ros::serialization::serializationLength(moving_edge); 00206 return size; 00207 } 00208 00209 typedef boost::shared_ptr< ::visp_tracker::InitRequest_<ContainerAllocator> > Ptr; 00210 typedef boost::shared_ptr< ::visp_tracker::InitRequest_<ContainerAllocator> const> ConstPtr; 00211 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00212 }; // struct InitRequest 00213 typedef ::visp_tracker::InitRequest_<std::allocator<void> > InitRequest; 00214 00215 typedef boost::shared_ptr< ::visp_tracker::InitRequest> InitRequestPtr; 00216 typedef boost::shared_ptr< ::visp_tracker::InitRequest const> InitRequestConstPtr; 00217 00218 00219 template <class ContainerAllocator> 00220 struct InitResponse_ { 00221 typedef InitResponse_<ContainerAllocator> Type; 00222 00223 InitResponse_() 00224 : initialization_succeed(false) 00225 { 00226 } 00227 00228 InitResponse_(const ContainerAllocator& _alloc) 00229 : initialization_succeed(false) 00230 { 00231 } 00232 00233 typedef uint8_t _initialization_succeed_type; 00234 uint8_t initialization_succeed; 00235 00236 00237 private: 00238 static const char* __s_getDataType_() { return "visp_tracker/InitResponse"; } 00239 public: 00240 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00241 00242 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00243 00244 private: 00245 static const char* __s_getMD5Sum_() { return "8e1a436e960986e0760f2970d0c88bf4"; } 00246 public: 00247 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00248 00249 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00250 00251 private: 00252 static const char* __s_getServerMD5Sum_() { return "d9f7c7c2435e9d0af6283a1aac362aac"; } 00253 public: 00254 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00255 00256 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00257 00258 private: 00259 static const char* __s_getMessageDefinition_() { return "\n\ 00260 bool initialization_succeed\n\ 00261 \n\ 00262 \n\ 00263 "; } 00264 public: 00265 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00266 00267 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00268 00269 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00270 { 00271 ros::serialization::OStream stream(write_ptr, 1000000000); 00272 ros::serialization::serialize(stream, initialization_succeed); 00273 return stream.getData(); 00274 } 00275 00276 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00277 { 00278 ros::serialization::IStream stream(read_ptr, 1000000000); 00279 ros::serialization::deserialize(stream, initialization_succeed); 00280 return stream.getData(); 00281 } 00282 00283 ROS_DEPRECATED virtual uint32_t serializationLength() const 00284 { 00285 uint32_t size = 0; 00286 size += ros::serialization::serializationLength(initialization_succeed); 00287 return size; 00288 } 00289 00290 typedef boost::shared_ptr< ::visp_tracker::InitResponse_<ContainerAllocator> > Ptr; 00291 typedef boost::shared_ptr< ::visp_tracker::InitResponse_<ContainerAllocator> const> ConstPtr; 00292 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00293 }; // struct InitResponse 00294 typedef ::visp_tracker::InitResponse_<std::allocator<void> > InitResponse; 00295 00296 typedef boost::shared_ptr< ::visp_tracker::InitResponse> InitResponsePtr; 00297 typedef boost::shared_ptr< ::visp_tracker::InitResponse const> InitResponseConstPtr; 00298 00299 struct Init 00300 { 00301 00302 typedef InitRequest Request; 00303 typedef InitResponse Response; 00304 Request request; 00305 Response response; 00306 00307 typedef Request RequestType; 00308 typedef Response ResponseType; 00309 }; // struct Init 00310 } // namespace visp_tracker 00311 00312 namespace ros 00313 { 00314 namespace message_traits 00315 { 00316 template<class ContainerAllocator> struct IsMessage< ::visp_tracker::InitRequest_<ContainerAllocator> > : public TrueType {}; 00317 template<class ContainerAllocator> struct IsMessage< ::visp_tracker::InitRequest_<ContainerAllocator> const> : public TrueType {}; 00318 template<class ContainerAllocator> 00319 struct MD5Sum< ::visp_tracker::InitRequest_<ContainerAllocator> > { 00320 static const char* value() 00321 { 00322 return "440a9fdc3875f06ac1d9d7ab02a58456"; 00323 } 00324 00325 static const char* value(const ::visp_tracker::InitRequest_<ContainerAllocator> &) { return value(); } 00326 static const uint64_t static_value1 = 0x440a9fdc3875f06aULL; 00327 static const uint64_t static_value2 = 0xc1d9d7ab02a58456ULL; 00328 }; 00329 00330 template<class ContainerAllocator> 00331 struct DataType< ::visp_tracker::InitRequest_<ContainerAllocator> > { 00332 static const char* value() 00333 { 00334 return "visp_tracker/InitRequest"; 00335 } 00336 00337 static const char* value(const ::visp_tracker::InitRequest_<ContainerAllocator> &) { return value(); } 00338 }; 00339 00340 template<class ContainerAllocator> 00341 struct Definition< ::visp_tracker::InitRequest_<ContainerAllocator> > { 00342 static const char* value() 00343 { 00344 return "\n\ 00345 \n\ 00346 \n\ 00347 \n\ 00348 \n\ 00349 \n\ 00350 \n\ 00351 \n\ 00352 \n\ 00353 geometry_msgs/Transform initial_cMo\n\ 00354 \n\ 00355 \n\ 00356 MovingEdge moving_edge\n\ 00357 \n\ 00358 ================================================================================\n\ 00359 MSG: geometry_msgs/Transform\n\ 00360 # This represents the transform between two coordinate frames in free space.\n\ 00361 \n\ 00362 Vector3 translation\n\ 00363 Quaternion rotation\n\ 00364 \n\ 00365 ================================================================================\n\ 00366 MSG: geometry_msgs/Vector3\n\ 00367 # This represents a vector in free space. \n\ 00368 \n\ 00369 float64 x\n\ 00370 float64 y\n\ 00371 float64 z\n\ 00372 ================================================================================\n\ 00373 MSG: geometry_msgs/Quaternion\n\ 00374 # This represents an orientation in free space in quaternion form.\n\ 00375 \n\ 00376 float64 x\n\ 00377 float64 y\n\ 00378 float64 z\n\ 00379 float64 w\n\ 00380 \n\ 00381 ================================================================================\n\ 00382 MSG: visp_tracker/MovingEdge\n\ 00383 # This message contains tracking parameters.\n\ 00384 #\n\ 00385 # These parameters determine how precise, how fast and how\n\ 00386 # reliable will be the tracking.\n\ 00387 #\n\ 00388 # It should be tuned carefully and can be changed dynamically.\n\ 00389 #\n\ 00390 # For more details, see the ViSP documentation:\n\ 00391 # http://www.irisa.fr/lagadic/visp/publication.html\n\ 00392 \n\ 00393 \n\ 00394 # Moving edge parameters.\n\ 00395 \n\ 00396 int64 mask_size # Mask size (in pixel) used to compute the image gradient\n\ 00397 # and determine the object contour.\n\ 00398 # A larger mask size is better for larger images.\n\ 00399 # 3 pixels is enough for 640x480 images.\n\ 00400 # Increasing this value makes the tracking slower.\n\ 00401 #\n\ 00402 # Caution: this value cannot be changed dynamically\n\ 00403 # without resetting the tracking.\n\ 00404 \n\ 00405 int64 n_mask # Number of masks applied to determine the object contour.\n\ 00406 # Increasing this value makes the tracking slower.\n\ 00407 \n\ 00408 int64 range # Maximum seek distance on both sides of the reference pixel.\n\ 00409 # It should match the maximum distance in pixel between\n\ 00410 # the current position of the feature projection and\n\ 00411 # its next position.\n\ 00412 # I.e. if the object moves fast and your tracking\n\ 00413 # frequency is low, this value should be increased.\n\ 00414 # Increasing this value makes the tracking slower.\n\ 00415 \n\ 00416 float64 threshold # Value used to determine if a moving edge is valid\n\ 00417 # or not.\n\ 00418 \n\ 00419 float64 mu1 # Minimum image contrast allowed to detect a contour.\n\ 00420 float64 mu2 # Maximum image contrast allowed to detect a contour.\n\ 00421 \n\ 00422 int64 sample_step # Minimum distance in pixel between two\n\ 00423 # discretization points.\n\ 00424 # It avoids having too many discretization points when\n\ 00425 # the tracked object is far away (and its projection\n\ 00426 # in the image is small).\n\ 00427 # Increasing this value makes the tracking *faster*.\n\ 00428 \n\ 00429 int64 ntotal_sample # How many discretization points are used to track the\n\ 00430 # feature.\n\ 00431 # Higher is better but slow down the tracking.\n\ 00432 # The best value depends on your model and its distance\n\ 00433 # with respect to the camera.\n\ 00434 # Increasing this value makes the tracking slower.\n\ 00435 \n\ 00436 int64 strip # How many pixels are ignored around the borders.\n\ 00437 float64 min_samplestep # Minimum allowed samplestep. Useful to specify\n\ 00438 # a lower bound when the samplestep is changed\n\ 00439 # dynamically.\n\ 00440 # This is not done by visp_tracker currently.\n\ 00441 float64 aberration # Ignored.\n\ 00442 float64 init_aberration # Ignored.\n\ 00443 \n\ 00444 \n\ 00445 # Tracker parameters.\n\ 00446 \n\ 00447 float64 lambda # Gain used to compute the control law.\n\ 00448 float64 first_threshold # What proportion of points should be valid to\n\ 00449 # acccept an initial pose.\n\ 00450 # Value should be between 0 et 1.\n\ 00451 \n\ 00452 "; 00453 } 00454 00455 static const char* value(const ::visp_tracker::InitRequest_<ContainerAllocator> &) { return value(); } 00456 }; 00457 00458 template<class ContainerAllocator> struct IsFixedSize< ::visp_tracker::InitRequest_<ContainerAllocator> > : public TrueType {}; 00459 } // namespace message_traits 00460 } // namespace ros 00461 00462 00463 namespace ros 00464 { 00465 namespace message_traits 00466 { 00467 template<class ContainerAllocator> struct IsMessage< ::visp_tracker::InitResponse_<ContainerAllocator> > : public TrueType {}; 00468 template<class ContainerAllocator> struct IsMessage< ::visp_tracker::InitResponse_<ContainerAllocator> const> : public TrueType {}; 00469 template<class ContainerAllocator> 00470 struct MD5Sum< ::visp_tracker::InitResponse_<ContainerAllocator> > { 00471 static const char* value() 00472 { 00473 return "8e1a436e960986e0760f2970d0c88bf4"; 00474 } 00475 00476 static const char* value(const ::visp_tracker::InitResponse_<ContainerAllocator> &) { return value(); } 00477 static const uint64_t static_value1 = 0x8e1a436e960986e0ULL; 00478 static const uint64_t static_value2 = 0x760f2970d0c88bf4ULL; 00479 }; 00480 00481 template<class ContainerAllocator> 00482 struct DataType< ::visp_tracker::InitResponse_<ContainerAllocator> > { 00483 static const char* value() 00484 { 00485 return "visp_tracker/InitResponse"; 00486 } 00487 00488 static const char* value(const ::visp_tracker::InitResponse_<ContainerAllocator> &) { return value(); } 00489 }; 00490 00491 template<class ContainerAllocator> 00492 struct Definition< ::visp_tracker::InitResponse_<ContainerAllocator> > { 00493 static const char* value() 00494 { 00495 return "\n\ 00496 bool initialization_succeed\n\ 00497 \n\ 00498 \n\ 00499 "; 00500 } 00501 00502 static const char* value(const ::visp_tracker::InitResponse_<ContainerAllocator> &) { return value(); } 00503 }; 00504 00505 template<class ContainerAllocator> struct IsFixedSize< ::visp_tracker::InitResponse_<ContainerAllocator> > : public TrueType {}; 00506 } // namespace message_traits 00507 } // namespace ros 00508 00509 namespace ros 00510 { 00511 namespace serialization 00512 { 00513 00514 template<class ContainerAllocator> struct Serializer< ::visp_tracker::InitRequest_<ContainerAllocator> > 00515 { 00516 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00517 { 00518 stream.next(m.initial_cMo); 00519 stream.next(m.moving_edge); 00520 } 00521 00522 ROS_DECLARE_ALLINONE_SERIALIZER; 00523 }; // struct InitRequest_ 00524 } // namespace serialization 00525 } // namespace ros 00526 00527 00528 namespace ros 00529 { 00530 namespace serialization 00531 { 00532 00533 template<class ContainerAllocator> struct Serializer< ::visp_tracker::InitResponse_<ContainerAllocator> > 00534 { 00535 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00536 { 00537 stream.next(m.initialization_succeed); 00538 } 00539 00540 ROS_DECLARE_ALLINONE_SERIALIZER; 00541 }; // struct InitResponse_ 00542 } // namespace serialization 00543 } // namespace ros 00544 00545 namespace ros 00546 { 00547 namespace service_traits 00548 { 00549 template<> 00550 struct MD5Sum<visp_tracker::Init> { 00551 static const char* value() 00552 { 00553 return "d9f7c7c2435e9d0af6283a1aac362aac"; 00554 } 00555 00556 static const char* value(const visp_tracker::Init&) { return value(); } 00557 }; 00558 00559 template<> 00560 struct DataType<visp_tracker::Init> { 00561 static const char* value() 00562 { 00563 return "visp_tracker/Init"; 00564 } 00565 00566 static const char* value(const visp_tracker::Init&) { return value(); } 00567 }; 00568 00569 template<class ContainerAllocator> 00570 struct MD5Sum<visp_tracker::InitRequest_<ContainerAllocator> > { 00571 static const char* value() 00572 { 00573 return "d9f7c7c2435e9d0af6283a1aac362aac"; 00574 } 00575 00576 static const char* value(const visp_tracker::InitRequest_<ContainerAllocator> &) { return value(); } 00577 }; 00578 00579 template<class ContainerAllocator> 00580 struct DataType<visp_tracker::InitRequest_<ContainerAllocator> > { 00581 static const char* value() 00582 { 00583 return "visp_tracker/Init"; 00584 } 00585 00586 static const char* value(const visp_tracker::InitRequest_<ContainerAllocator> &) { return value(); } 00587 }; 00588 00589 template<class ContainerAllocator> 00590 struct MD5Sum<visp_tracker::InitResponse_<ContainerAllocator> > { 00591 static const char* value() 00592 { 00593 return "d9f7c7c2435e9d0af6283a1aac362aac"; 00594 } 00595 00596 static const char* value(const visp_tracker::InitResponse_<ContainerAllocator> &) { return value(); } 00597 }; 00598 00599 template<class ContainerAllocator> 00600 struct DataType<visp_tracker::InitResponse_<ContainerAllocator> > { 00601 static const char* value() 00602 { 00603 return "visp_tracker/Init"; 00604 } 00605 00606 static const char* value(const visp_tracker::InitResponse_<ContainerAllocator> &) { return value(); } 00607 }; 00608 00609 } // namespace service_traits 00610 } // namespace ros 00611 00612 #endif // VISP_TRACKER_SERVICE_INIT_H 00613