00001
00002 #ifndef COB_OBJECT_DETECTION_MSGS_SERVICE_BATESTENVIRONMENT_H
00003 #define COB_OBJECT_DETECTION_MSGS_SERVICE_BATESTENVIRONMENT_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 "std_msgs/String.h"
00022
00023 namespace cob_object_detection_msgs
00024 {
00025 template <class ContainerAllocator>
00026 struct BaTestEnvironmentRequest_ {
00027 typedef BaTestEnvironmentRequest_<ContainerAllocator> Type;
00028
00029 BaTestEnvironmentRequest_()
00030 : number_points(0)
00031 , frame_view_number(0.0)
00032 , cone_points_per_plane(0.0)
00033 , limit_error_matching(0.0)
00034 , ba_kernel_param(0.0)
00035 , ba_num_iter(0)
00036 , ba_initial_mu(0.0)
00037 , ba_final_mu_factor(0.0)
00038 , ba_tau(0.0)
00039 , angle_sigma_degree(0.0)
00040 , translate_sigma_m(0.0)
00041 , obs_point_sigma_m(0.0)
00042 , world_point_sigma_m(0.0)
00043 {
00044 }
00045
00046 BaTestEnvironmentRequest_(const ContainerAllocator& _alloc)
00047 : number_points(0)
00048 , frame_view_number(0.0)
00049 , cone_points_per_plane(0.0)
00050 , limit_error_matching(0.0)
00051 , ba_kernel_param(0.0)
00052 , ba_num_iter(0)
00053 , ba_initial_mu(0.0)
00054 , ba_final_mu_factor(0.0)
00055 , ba_tau(0.0)
00056 , angle_sigma_degree(0.0)
00057 , translate_sigma_m(0.0)
00058 , obs_point_sigma_m(0.0)
00059 , world_point_sigma_m(0.0)
00060 {
00061 }
00062
00063 typedef int32_t _number_points_type;
00064 int32_t number_points;
00065
00066 typedef float _frame_view_number_type;
00067 float frame_view_number;
00068
00069 typedef float _cone_points_per_plane_type;
00070 float cone_points_per_plane;
00071
00072 typedef float _limit_error_matching_type;
00073 float limit_error_matching;
00074
00075 typedef float _ba_kernel_param_type;
00076 float ba_kernel_param;
00077
00078 typedef int32_t _ba_num_iter_type;
00079 int32_t ba_num_iter;
00080
00081 typedef float _ba_initial_mu_type;
00082 float ba_initial_mu;
00083
00084 typedef float _ba_final_mu_factor_type;
00085 float ba_final_mu_factor;
00086
00087 typedef float _ba_tau_type;
00088 float ba_tau;
00089
00090 typedef float _angle_sigma_degree_type;
00091 float angle_sigma_degree;
00092
00093 typedef float _translate_sigma_m_type;
00094 float translate_sigma_m;
00095
00096 typedef float _obs_point_sigma_m_type;
00097 float obs_point_sigma_m;
00098
00099 typedef float _world_point_sigma_m_type;
00100 float world_point_sigma_m;
00101
00102
00103 typedef boost::shared_ptr< ::cob_object_detection_msgs::BaTestEnvironmentRequest_<ContainerAllocator> > Ptr;
00104 typedef boost::shared_ptr< ::cob_object_detection_msgs::BaTestEnvironmentRequest_<ContainerAllocator> const> ConstPtr;
00105 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00106 };
00107 typedef ::cob_object_detection_msgs::BaTestEnvironmentRequest_<std::allocator<void> > BaTestEnvironmentRequest;
00108
00109 typedef boost::shared_ptr< ::cob_object_detection_msgs::BaTestEnvironmentRequest> BaTestEnvironmentRequestPtr;
00110 typedef boost::shared_ptr< ::cob_object_detection_msgs::BaTestEnvironmentRequest const> BaTestEnvironmentRequestConstPtr;
00111
00112
00113 template <class ContainerAllocator>
00114 struct BaTestEnvironmentResponse_ {
00115 typedef BaTestEnvironmentResponse_<ContainerAllocator> Type;
00116
00117 BaTestEnvironmentResponse_()
00118 : mean_error(0.0)
00119 , std_dev(0.0)
00120 , min_error(0.0)
00121 , max_error(0.0)
00122 , runs_count(0.0)
00123 , runs_sum(0.0)
00124 , runs_sum2(0.0)
00125 , time_duration(0.0)
00126 , observations(0)
00127 , false_matchings(0)
00128 , result()
00129 {
00130 }
00131
00132 BaTestEnvironmentResponse_(const ContainerAllocator& _alloc)
00133 : mean_error(0.0)
00134 , std_dev(0.0)
00135 , min_error(0.0)
00136 , max_error(0.0)
00137 , runs_count(0.0)
00138 , runs_sum(0.0)
00139 , runs_sum2(0.0)
00140 , time_duration(0.0)
00141 , observations(0)
00142 , false_matchings(0)
00143 , result(_alloc)
00144 {
00145 }
00146
00147 typedef float _mean_error_type;
00148 float mean_error;
00149
00150 typedef float _std_dev_type;
00151 float std_dev;
00152
00153 typedef float _min_error_type;
00154 float min_error;
00155
00156 typedef float _max_error_type;
00157 float max_error;
00158
00159 typedef float _runs_count_type;
00160 float runs_count;
00161
00162 typedef float _runs_sum_type;
00163 float runs_sum;
00164
00165 typedef float _runs_sum2_type;
00166 float runs_sum2;
00167
00168 typedef float _time_duration_type;
00169 float time_duration;
00170
00171 typedef int32_t _observations_type;
00172 int32_t observations;
00173
00174 typedef int32_t _false_matchings_type;
00175 int32_t false_matchings;
00176
00177 typedef ::std_msgs::String_<ContainerAllocator> _result_type;
00178 ::std_msgs::String_<ContainerAllocator> result;
00179
00180
00181 typedef boost::shared_ptr< ::cob_object_detection_msgs::BaTestEnvironmentResponse_<ContainerAllocator> > Ptr;
00182 typedef boost::shared_ptr< ::cob_object_detection_msgs::BaTestEnvironmentResponse_<ContainerAllocator> const> ConstPtr;
00183 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00184 };
00185 typedef ::cob_object_detection_msgs::BaTestEnvironmentResponse_<std::allocator<void> > BaTestEnvironmentResponse;
00186
00187 typedef boost::shared_ptr< ::cob_object_detection_msgs::BaTestEnvironmentResponse> BaTestEnvironmentResponsePtr;
00188 typedef boost::shared_ptr< ::cob_object_detection_msgs::BaTestEnvironmentResponse const> BaTestEnvironmentResponseConstPtr;
00189
00190 struct BaTestEnvironment
00191 {
00192
00193 typedef BaTestEnvironmentRequest Request;
00194 typedef BaTestEnvironmentResponse Response;
00195 Request request;
00196 Response response;
00197
00198 typedef Request RequestType;
00199 typedef Response ResponseType;
00200 };
00201 }
00202
00203 namespace ros
00204 {
00205 namespace message_traits
00206 {
00207 template<class ContainerAllocator> struct IsMessage< ::cob_object_detection_msgs::BaTestEnvironmentRequest_<ContainerAllocator> > : public TrueType {};
00208 template<class ContainerAllocator> struct IsMessage< ::cob_object_detection_msgs::BaTestEnvironmentRequest_<ContainerAllocator> const> : public TrueType {};
00209 template<class ContainerAllocator>
00210 struct MD5Sum< ::cob_object_detection_msgs::BaTestEnvironmentRequest_<ContainerAllocator> > {
00211 static const char* value()
00212 {
00213 return "65aeb9eaa6cbc248861e82cf7f7464c0";
00214 }
00215
00216 static const char* value(const ::cob_object_detection_msgs::BaTestEnvironmentRequest_<ContainerAllocator> &) { return value(); }
00217 static const uint64_t static_value1 = 0x65aeb9eaa6cbc248ULL;
00218 static const uint64_t static_value2 = 0x861e82cf7f7464c0ULL;
00219 };
00220
00221 template<class ContainerAllocator>
00222 struct DataType< ::cob_object_detection_msgs::BaTestEnvironmentRequest_<ContainerAllocator> > {
00223 static const char* value()
00224 {
00225 return "cob_object_detection_msgs/BaTestEnvironmentRequest";
00226 }
00227
00228 static const char* value(const ::cob_object_detection_msgs::BaTestEnvironmentRequest_<ContainerAllocator> &) { return value(); }
00229 };
00230
00231 template<class ContainerAllocator>
00232 struct Definition< ::cob_object_detection_msgs::BaTestEnvironmentRequest_<ContainerAllocator> > {
00233 static const char* value()
00234 {
00235 return "\n\
00236 \n\
00237 int32 number_points\n\
00238 float32 frame_view_number\n\
00239 float32 cone_points_per_plane\n\
00240 \n\
00241 \n\
00242 float32 limit_error_matching\n\
00243 \n\
00244 float32 ba_kernel_param\n\
00245 int32 ba_num_iter\n\
00246 float32 ba_initial_mu\n\
00247 float32 ba_final_mu_factor\n\
00248 float32 ba_tau\n\
00249 \n\
00250 float32 angle_sigma_degree\n\
00251 float32 translate_sigma_m\n\
00252 float32 obs_point_sigma_m\n\
00253 float32 world_point_sigma_m\n\
00254 \n\
00255 \n\
00256 ";
00257 }
00258
00259 static const char* value(const ::cob_object_detection_msgs::BaTestEnvironmentRequest_<ContainerAllocator> &) { return value(); }
00260 };
00261
00262 template<class ContainerAllocator> struct IsFixedSize< ::cob_object_detection_msgs::BaTestEnvironmentRequest_<ContainerAllocator> > : public TrueType {};
00263 }
00264 }
00265
00266
00267 namespace ros
00268 {
00269 namespace message_traits
00270 {
00271 template<class ContainerAllocator> struct IsMessage< ::cob_object_detection_msgs::BaTestEnvironmentResponse_<ContainerAllocator> > : public TrueType {};
00272 template<class ContainerAllocator> struct IsMessage< ::cob_object_detection_msgs::BaTestEnvironmentResponse_<ContainerAllocator> const> : public TrueType {};
00273 template<class ContainerAllocator>
00274 struct MD5Sum< ::cob_object_detection_msgs::BaTestEnvironmentResponse_<ContainerAllocator> > {
00275 static const char* value()
00276 {
00277 return "73db4f13e99b7e554aa13b596abbef41";
00278 }
00279
00280 static const char* value(const ::cob_object_detection_msgs::BaTestEnvironmentResponse_<ContainerAllocator> &) { return value(); }
00281 static const uint64_t static_value1 = 0x73db4f13e99b7e55ULL;
00282 static const uint64_t static_value2 = 0x4aa13b596abbef41ULL;
00283 };
00284
00285 template<class ContainerAllocator>
00286 struct DataType< ::cob_object_detection_msgs::BaTestEnvironmentResponse_<ContainerAllocator> > {
00287 static const char* value()
00288 {
00289 return "cob_object_detection_msgs/BaTestEnvironmentResponse";
00290 }
00291
00292 static const char* value(const ::cob_object_detection_msgs::BaTestEnvironmentResponse_<ContainerAllocator> &) { return value(); }
00293 };
00294
00295 template<class ContainerAllocator>
00296 struct Definition< ::cob_object_detection_msgs::BaTestEnvironmentResponse_<ContainerAllocator> > {
00297 static const char* value()
00298 {
00299 return "float32 mean_error\n\
00300 float32 std_dev\n\
00301 float32 min_error\n\
00302 float32 max_error\n\
00303 float32 runs_count\n\
00304 float32 runs_sum\n\
00305 float32 runs_sum2\n\
00306 \n\
00307 float32 time_duration\n\
00308 int32 observations\n\
00309 int32 false_matchings\n\
00310 \n\
00311 std_msgs/String result\n\
00312 \n\
00313 \n\
00314 ================================================================================\n\
00315 MSG: std_msgs/String\n\
00316 string data\n\
00317 \n\
00318 ";
00319 }
00320
00321 static const char* value(const ::cob_object_detection_msgs::BaTestEnvironmentResponse_<ContainerAllocator> &) { return value(); }
00322 };
00323
00324 }
00325 }
00326
00327 namespace ros
00328 {
00329 namespace serialization
00330 {
00331
00332 template<class ContainerAllocator> struct Serializer< ::cob_object_detection_msgs::BaTestEnvironmentRequest_<ContainerAllocator> >
00333 {
00334 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00335 {
00336 stream.next(m.number_points);
00337 stream.next(m.frame_view_number);
00338 stream.next(m.cone_points_per_plane);
00339 stream.next(m.limit_error_matching);
00340 stream.next(m.ba_kernel_param);
00341 stream.next(m.ba_num_iter);
00342 stream.next(m.ba_initial_mu);
00343 stream.next(m.ba_final_mu_factor);
00344 stream.next(m.ba_tau);
00345 stream.next(m.angle_sigma_degree);
00346 stream.next(m.translate_sigma_m);
00347 stream.next(m.obs_point_sigma_m);
00348 stream.next(m.world_point_sigma_m);
00349 }
00350
00351 ROS_DECLARE_ALLINONE_SERIALIZER;
00352 };
00353 }
00354 }
00355
00356
00357 namespace ros
00358 {
00359 namespace serialization
00360 {
00361
00362 template<class ContainerAllocator> struct Serializer< ::cob_object_detection_msgs::BaTestEnvironmentResponse_<ContainerAllocator> >
00363 {
00364 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00365 {
00366 stream.next(m.mean_error);
00367 stream.next(m.std_dev);
00368 stream.next(m.min_error);
00369 stream.next(m.max_error);
00370 stream.next(m.runs_count);
00371 stream.next(m.runs_sum);
00372 stream.next(m.runs_sum2);
00373 stream.next(m.time_duration);
00374 stream.next(m.observations);
00375 stream.next(m.false_matchings);
00376 stream.next(m.result);
00377 }
00378
00379 ROS_DECLARE_ALLINONE_SERIALIZER;
00380 };
00381 }
00382 }
00383
00384 namespace ros
00385 {
00386 namespace service_traits
00387 {
00388 template<>
00389 struct MD5Sum<cob_object_detection_msgs::BaTestEnvironment> {
00390 static const char* value()
00391 {
00392 return "e3abe6b136e84d507dcba74e019ba61e";
00393 }
00394
00395 static const char* value(const cob_object_detection_msgs::BaTestEnvironment&) { return value(); }
00396 };
00397
00398 template<>
00399 struct DataType<cob_object_detection_msgs::BaTestEnvironment> {
00400 static const char* value()
00401 {
00402 return "cob_object_detection_msgs/BaTestEnvironment";
00403 }
00404
00405 static const char* value(const cob_object_detection_msgs::BaTestEnvironment&) { return value(); }
00406 };
00407
00408 template<class ContainerAllocator>
00409 struct MD5Sum<cob_object_detection_msgs::BaTestEnvironmentRequest_<ContainerAllocator> > {
00410 static const char* value()
00411 {
00412 return "e3abe6b136e84d507dcba74e019ba61e";
00413 }
00414
00415 static const char* value(const cob_object_detection_msgs::BaTestEnvironmentRequest_<ContainerAllocator> &) { return value(); }
00416 };
00417
00418 template<class ContainerAllocator>
00419 struct DataType<cob_object_detection_msgs::BaTestEnvironmentRequest_<ContainerAllocator> > {
00420 static const char* value()
00421 {
00422 return "cob_object_detection_msgs/BaTestEnvironment";
00423 }
00424
00425 static const char* value(const cob_object_detection_msgs::BaTestEnvironmentRequest_<ContainerAllocator> &) { return value(); }
00426 };
00427
00428 template<class ContainerAllocator>
00429 struct MD5Sum<cob_object_detection_msgs::BaTestEnvironmentResponse_<ContainerAllocator> > {
00430 static const char* value()
00431 {
00432 return "e3abe6b136e84d507dcba74e019ba61e";
00433 }
00434
00435 static const char* value(const cob_object_detection_msgs::BaTestEnvironmentResponse_<ContainerAllocator> &) { return value(); }
00436 };
00437
00438 template<class ContainerAllocator>
00439 struct DataType<cob_object_detection_msgs::BaTestEnvironmentResponse_<ContainerAllocator> > {
00440 static const char* value()
00441 {
00442 return "cob_object_detection_msgs/BaTestEnvironment";
00443 }
00444
00445 static const char* value(const cob_object_detection_msgs::BaTestEnvironmentResponse_<ContainerAllocator> &) { return value(); }
00446 };
00447
00448 }
00449 }
00450
00451 #endif // COB_OBJECT_DETECTION_MSGS_SERVICE_BATESTENVIRONMENT_H
00452