Go to the documentation of this file.00001
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/MovingEdgeSettings.h"
00021 #include "visp_tracker/KltSettings.h"
00022
00023
00024
00025 namespace visp_tracker
00026 {
00027 template <class ContainerAllocator>
00028 struct InitRequest_ {
00029 typedef InitRequest_<ContainerAllocator> Type;
00030
00031 InitRequest_()
00032 : initial_cMo()
00033 , moving_edge()
00034 , klt_param()
00035 {
00036 }
00037
00038 InitRequest_(const ContainerAllocator& _alloc)
00039 : initial_cMo(_alloc)
00040 , moving_edge(_alloc)
00041 , klt_param(_alloc)
00042 {
00043 }
00044
00045 typedef ::geometry_msgs::Transform_<ContainerAllocator> _initial_cMo_type;
00046 ::geometry_msgs::Transform_<ContainerAllocator> initial_cMo;
00047
00048 typedef ::visp_tracker::MovingEdgeSettings_<ContainerAllocator> _moving_edge_type;
00049 ::visp_tracker::MovingEdgeSettings_<ContainerAllocator> moving_edge;
00050
00051 typedef ::visp_tracker::KltSettings_<ContainerAllocator> _klt_param_type;
00052 ::visp_tracker::KltSettings_<ContainerAllocator> klt_param;
00053
00054
00055 typedef boost::shared_ptr< ::visp_tracker::InitRequest_<ContainerAllocator> > Ptr;
00056 typedef boost::shared_ptr< ::visp_tracker::InitRequest_<ContainerAllocator> const> ConstPtr;
00057 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00058 };
00059 typedef ::visp_tracker::InitRequest_<std::allocator<void> > InitRequest;
00060
00061 typedef boost::shared_ptr< ::visp_tracker::InitRequest> InitRequestPtr;
00062 typedef boost::shared_ptr< ::visp_tracker::InitRequest const> InitRequestConstPtr;
00063
00064
00065 template <class ContainerAllocator>
00066 struct InitResponse_ {
00067 typedef InitResponse_<ContainerAllocator> Type;
00068
00069 InitResponse_()
00070 : initialization_succeed(false)
00071 {
00072 }
00073
00074 InitResponse_(const ContainerAllocator& _alloc)
00075 : initialization_succeed(false)
00076 {
00077 }
00078
00079 typedef uint8_t _initialization_succeed_type;
00080 uint8_t initialization_succeed;
00081
00082
00083 typedef boost::shared_ptr< ::visp_tracker::InitResponse_<ContainerAllocator> > Ptr;
00084 typedef boost::shared_ptr< ::visp_tracker::InitResponse_<ContainerAllocator> const> ConstPtr;
00085 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00086 };
00087 typedef ::visp_tracker::InitResponse_<std::allocator<void> > InitResponse;
00088
00089 typedef boost::shared_ptr< ::visp_tracker::InitResponse> InitResponsePtr;
00090 typedef boost::shared_ptr< ::visp_tracker::InitResponse const> InitResponseConstPtr;
00091
00092 struct Init
00093 {
00094
00095 typedef InitRequest Request;
00096 typedef InitResponse Response;
00097 Request request;
00098 Response response;
00099
00100 typedef Request RequestType;
00101 typedef Response ResponseType;
00102 };
00103 }
00104
00105 namespace ros
00106 {
00107 namespace message_traits
00108 {
00109 template<class ContainerAllocator> struct IsMessage< ::visp_tracker::InitRequest_<ContainerAllocator> > : public TrueType {};
00110 template<class ContainerAllocator> struct IsMessage< ::visp_tracker::InitRequest_<ContainerAllocator> const> : public TrueType {};
00111 template<class ContainerAllocator>
00112 struct MD5Sum< ::visp_tracker::InitRequest_<ContainerAllocator> > {
00113 static const char* value()
00114 {
00115 return "6ddad5ffb18cb18d2e35e4638ed71167";
00116 }
00117
00118 static const char* value(const ::visp_tracker::InitRequest_<ContainerAllocator> &) { return value(); }
00119 static const uint64_t static_value1 = 0x6ddad5ffb18cb18dULL;
00120 static const uint64_t static_value2 = 0x2e35e4638ed71167ULL;
00121 };
00122
00123 template<class ContainerAllocator>
00124 struct DataType< ::visp_tracker::InitRequest_<ContainerAllocator> > {
00125 static const char* value()
00126 {
00127 return "visp_tracker/InitRequest";
00128 }
00129
00130 static const char* value(const ::visp_tracker::InitRequest_<ContainerAllocator> &) { return value(); }
00131 };
00132
00133 template<class ContainerAllocator>
00134 struct Definition< ::visp_tracker::InitRequest_<ContainerAllocator> > {
00135 static const char* value()
00136 {
00137 return "\n\
00138 \n\
00139 \n\
00140 \n\
00141 \n\
00142 \n\
00143 \n\
00144 \n\
00145 \n\
00146 geometry_msgs/Transform initial_cMo\n\
00147 \n\
00148 \n\
00149 MovingEdgeSettings moving_edge\n\
00150 \n\
00151 \n\
00152 KltSettings klt_param\n\
00153 \n\
00154 ================================================================================\n\
00155 MSG: geometry_msgs/Transform\n\
00156 # This represents the transform between two coordinate frames in free space.\n\
00157 \n\
00158 Vector3 translation\n\
00159 Quaternion rotation\n\
00160 \n\
00161 ================================================================================\n\
00162 MSG: geometry_msgs/Vector3\n\
00163 # This represents a vector in free space. \n\
00164 \n\
00165 float64 x\n\
00166 float64 y\n\
00167 float64 z\n\
00168 ================================================================================\n\
00169 MSG: geometry_msgs/Quaternion\n\
00170 # This represents an orientation in free space in quaternion form.\n\
00171 \n\
00172 float64 x\n\
00173 float64 y\n\
00174 float64 z\n\
00175 float64 w\n\
00176 \n\
00177 ================================================================================\n\
00178 MSG: visp_tracker/MovingEdgeSettings\n\
00179 # This message contains tracking parameters.\n\
00180 #\n\
00181 # These parameters determine how precise, how fast and how\n\
00182 # reliable will be the tracking.\n\
00183 #\n\
00184 # It should be tuned carefully and can be changed dynamically.\n\
00185 #\n\
00186 # For more details, see the ViSP documentation:\n\
00187 # http://www.irisa.fr/lagadic/visp/publication.html\n\
00188 \n\
00189 \n\
00190 # Moving edge parameters.\n\
00191 \n\
00192 int64 mask_size # Mask size (in pixel) used to compute the image gradient\n\
00193 # and determine the object contour.\n\
00194 # A larger mask size is better for larger images.\n\
00195 # 3 pixels is enough for 640x480 images.\n\
00196 # Increasing this value makes the tracking slower.\n\
00197 #\n\
00198 # Caution: this value cannot be changed dynamically\n\
00199 # without resetting the tracking.\n\
00200 \n\
00201 int64 n_mask # Number of masks applied to determine the object contour.\n\
00202 # Increasing this value makes the tracking slower.\n\
00203 \n\
00204 int64 range # Maximum seek distance on both sides of the reference pixel.\n\
00205 # It should match the maximum distance in pixel between\n\
00206 # the current position of the feature projection and\n\
00207 # its next position.\n\
00208 # I.e. if the object moves fast and your tracking\n\
00209 # frequency is low, this value should be increased.\n\
00210 # Increasing this value makes the tracking slower.\n\
00211 \n\
00212 float64 threshold # Value used to determine if a moving edge is valid\n\
00213 # or not.\n\
00214 \n\
00215 float64 mu1 # Minimum image contrast allowed to detect a contour.\n\
00216 float64 mu2 # Maximum image contrast allowed to detect a contour.\n\
00217 \n\
00218 int64 sample_step # Minimum distance in pixel between two\n\
00219 # discretization points.\n\
00220 # It avoids having too many discretization points when\n\
00221 # the tracked object is far away (and its projection\n\
00222 # in the image is small).\n\
00223 # Increasing this value makes the tracking *faster*.\n\
00224 \n\
00225 int64 ntotal_sample # How many discretization points are used to track the\n\
00226 # feature.\n\
00227 # Higher is better but slow down the tracking.\n\
00228 # The best value depends on your model and its distance\n\
00229 # with respect to the camera.\n\
00230 # Increasing this value makes the tracking slower.\n\
00231 \n\
00232 int64 strip # How many pixels are ignored around the borders.\n\
00233 float64 min_samplestep # Minimum allowed samplestep. Useful to specify\n\
00234 # a lower bound when the samplestep is changed\n\
00235 # dynamically.\n\
00236 # This is not done by visp_tracker currently.\n\
00237 float64 aberration # Ignored.\n\
00238 float64 init_aberration # Ignored.\n\
00239 \n\
00240 \n\
00241 # Tracker parameters.\n\
00242 \n\
00243 float64 lambda # Gain used to compute the control law.\n\
00244 float64 first_threshold # What proportion of points should be valid to\n\
00245 # acccept an initial pose.\n\
00246 # Value should be between 0 et 1.\n\
00247 \n\
00248 \n\
00249 ================================================================================\n\
00250 MSG: visp_tracker/KltSettings\n\
00251 # This message contains tracking parameters.\n\
00252 #\n\
00253 # These parameters determine how precise, how fast and how\n\
00254 # reliable will be the tracking.\n\
00255 #\n\
00256 # It should be tuned carefully and can be changed dynamically.\n\
00257 #\n\
00258 # For more details, see the ViSP documentation:\n\
00259 # http://www.irisa.fr/lagadic/visp/publication.html\n\
00260 \n\
00261 # Klt Parameters.\n\
00262 \n\
00263 int64 max_features # Maximum number of features\n\
00264 int64 window_size # Window size\n\
00265 float64 quality # Quality of the tracker\n\
00266 float64 min_distance # Minimum distance betwenn two points\n\
00267 float64 harris # Harris free parameters\n\
00268 int64 size_block # Block size\n\
00269 int64 pyramid_lvl # Pyramid levels\n\
00270 \n\
00271 float64 angle_appear # Angle to test faces apparition\n\
00272 float64 angle_disappear # Angle to test faces disparition\n\
00273 int64 mask_border # Mask Border\n\
00274 \n\
00275 \n\
00276 ";
00277 }
00278
00279 static const char* value(const ::visp_tracker::InitRequest_<ContainerAllocator> &) { return value(); }
00280 };
00281
00282 template<class ContainerAllocator> struct IsFixedSize< ::visp_tracker::InitRequest_<ContainerAllocator> > : public TrueType {};
00283 }
00284 }
00285
00286
00287 namespace ros
00288 {
00289 namespace message_traits
00290 {
00291 template<class ContainerAllocator> struct IsMessage< ::visp_tracker::InitResponse_<ContainerAllocator> > : public TrueType {};
00292 template<class ContainerAllocator> struct IsMessage< ::visp_tracker::InitResponse_<ContainerAllocator> const> : public TrueType {};
00293 template<class ContainerAllocator>
00294 struct MD5Sum< ::visp_tracker::InitResponse_<ContainerAllocator> > {
00295 static const char* value()
00296 {
00297 return "8e1a436e960986e0760f2970d0c88bf4";
00298 }
00299
00300 static const char* value(const ::visp_tracker::InitResponse_<ContainerAllocator> &) { return value(); }
00301 static const uint64_t static_value1 = 0x8e1a436e960986e0ULL;
00302 static const uint64_t static_value2 = 0x760f2970d0c88bf4ULL;
00303 };
00304
00305 template<class ContainerAllocator>
00306 struct DataType< ::visp_tracker::InitResponse_<ContainerAllocator> > {
00307 static const char* value()
00308 {
00309 return "visp_tracker/InitResponse";
00310 }
00311
00312 static const char* value(const ::visp_tracker::InitResponse_<ContainerAllocator> &) { return value(); }
00313 };
00314
00315 template<class ContainerAllocator>
00316 struct Definition< ::visp_tracker::InitResponse_<ContainerAllocator> > {
00317 static const char* value()
00318 {
00319 return "\n\
00320 bool initialization_succeed\n\
00321 \n\
00322 \n\
00323 ";
00324 }
00325
00326 static const char* value(const ::visp_tracker::InitResponse_<ContainerAllocator> &) { return value(); }
00327 };
00328
00329 template<class ContainerAllocator> struct IsFixedSize< ::visp_tracker::InitResponse_<ContainerAllocator> > : public TrueType {};
00330 }
00331 }
00332
00333 namespace ros
00334 {
00335 namespace serialization
00336 {
00337
00338 template<class ContainerAllocator> struct Serializer< ::visp_tracker::InitRequest_<ContainerAllocator> >
00339 {
00340 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00341 {
00342 stream.next(m.initial_cMo);
00343 stream.next(m.moving_edge);
00344 stream.next(m.klt_param);
00345 }
00346
00347 ROS_DECLARE_ALLINONE_SERIALIZER;
00348 };
00349 }
00350 }
00351
00352
00353 namespace ros
00354 {
00355 namespace serialization
00356 {
00357
00358 template<class ContainerAllocator> struct Serializer< ::visp_tracker::InitResponse_<ContainerAllocator> >
00359 {
00360 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00361 {
00362 stream.next(m.initialization_succeed);
00363 }
00364
00365 ROS_DECLARE_ALLINONE_SERIALIZER;
00366 };
00367 }
00368 }
00369
00370 namespace ros
00371 {
00372 namespace service_traits
00373 {
00374 template<>
00375 struct MD5Sum<visp_tracker::Init> {
00376 static const char* value()
00377 {
00378 return "b98829be051ed8dd7eb9b953f576de21";
00379 }
00380
00381 static const char* value(const visp_tracker::Init&) { return value(); }
00382 };
00383
00384 template<>
00385 struct DataType<visp_tracker::Init> {
00386 static const char* value()
00387 {
00388 return "visp_tracker/Init";
00389 }
00390
00391 static const char* value(const visp_tracker::Init&) { return value(); }
00392 };
00393
00394 template<class ContainerAllocator>
00395 struct MD5Sum<visp_tracker::InitRequest_<ContainerAllocator> > {
00396 static const char* value()
00397 {
00398 return "b98829be051ed8dd7eb9b953f576de21";
00399 }
00400
00401 static const char* value(const visp_tracker::InitRequest_<ContainerAllocator> &) { return value(); }
00402 };
00403
00404 template<class ContainerAllocator>
00405 struct DataType<visp_tracker::InitRequest_<ContainerAllocator> > {
00406 static const char* value()
00407 {
00408 return "visp_tracker/Init";
00409 }
00410
00411 static const char* value(const visp_tracker::InitRequest_<ContainerAllocator> &) { return value(); }
00412 };
00413
00414 template<class ContainerAllocator>
00415 struct MD5Sum<visp_tracker::InitResponse_<ContainerAllocator> > {
00416 static const char* value()
00417 {
00418 return "b98829be051ed8dd7eb9b953f576de21";
00419 }
00420
00421 static const char* value(const visp_tracker::InitResponse_<ContainerAllocator> &) { return value(); }
00422 };
00423
00424 template<class ContainerAllocator>
00425 struct DataType<visp_tracker::InitResponse_<ContainerAllocator> > {
00426 static const char* value()
00427 {
00428 return "visp_tracker/Init";
00429 }
00430
00431 static const char* value(const visp_tracker::InitResponse_<ContainerAllocator> &) { return value(); }
00432 };
00433
00434 }
00435 }
00436
00437 #endif // VISP_TRACKER_SERVICE_INIT_H
00438