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