00001
00002 #ifndef HOUSEHOLD_OBJECTS_DATABASE_MSGS_SERVICE_SAVESCAN_H
00003 #define HOUSEHOLD_OBJECTS_DATABASE_MSGS_SERVICE_SAVESCAN_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/PoseStamped.h"
00016
00017
00018 #include "household_objects_database_msgs/DatabaseReturnCode.h"
00019
00020 namespace household_objects_database_msgs
00021 {
00022 template <class ContainerAllocator>
00023 struct SaveScanRequest_ : public ros::Message
00024 {
00025 typedef SaveScanRequest_<ContainerAllocator> Type;
00026
00027 SaveScanRequest_()
00028 : scaled_model_id(0)
00029 , ground_truth_pose()
00030 , bagfile_location()
00031 , scan_source()
00032 , cloud_topic()
00033 {
00034 }
00035
00036 SaveScanRequest_(const ContainerAllocator& _alloc)
00037 : scaled_model_id(0)
00038 , ground_truth_pose(_alloc)
00039 , bagfile_location(_alloc)
00040 , scan_source(_alloc)
00041 , cloud_topic(_alloc)
00042 {
00043 }
00044
00045 typedef int32_t _scaled_model_id_type;
00046 int32_t scaled_model_id;
00047
00048 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _ground_truth_pose_type;
00049 ::geometry_msgs::PoseStamped_<ContainerAllocator> ground_truth_pose;
00050
00051 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _bagfile_location_type;
00052 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > bagfile_location;
00053
00054 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _scan_source_type;
00055 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > scan_source;
00056
00057 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _cloud_topic_type;
00058 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > cloud_topic;
00059
00060
00061 private:
00062 static const char* __s_getDataType_() { return "household_objects_database_msgs/SaveScanRequest"; }
00063 public:
00064 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00065
00066 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00067
00068 private:
00069 static const char* __s_getMD5Sum_() { return "492f49d320aa26325df5fb078c297fa5"; }
00070 public:
00071 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00072
00073 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00074
00075 private:
00076 static const char* __s_getServerMD5Sum_() { return "855c7b6f2658d8a9de03dd9a5f7b1f1e"; }
00077 public:
00078 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00079
00080 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00081
00082 private:
00083 static const char* __s_getMessageDefinition_() { return "\n\
00084 \n\
00085 \n\
00086 int32 scaled_model_id\n\
00087 \n\
00088 \n\
00089 geometry_msgs/PoseStamped ground_truth_pose\n\
00090 \n\
00091 \n\
00092 string bagfile_location\n\
00093 \n\
00094 \n\
00095 string scan_source\n\
00096 \n\
00097 \n\
00098 string cloud_topic\n\
00099 \n\
00100 \n\
00101 ================================================================================\n\
00102 MSG: geometry_msgs/PoseStamped\n\
00103 # A Pose with reference coordinate frame and timestamp\n\
00104 Header header\n\
00105 Pose pose\n\
00106 \n\
00107 ================================================================================\n\
00108 MSG: std_msgs/Header\n\
00109 # Standard metadata for higher-level stamped data types.\n\
00110 # This is generally used to communicate timestamped data \n\
00111 # in a particular coordinate frame.\n\
00112 # \n\
00113 # sequence ID: consecutively increasing ID \n\
00114 uint32 seq\n\
00115 #Two-integer timestamp that is expressed as:\n\
00116 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00117 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00118 # time-handling sugar is provided by the client library\n\
00119 time stamp\n\
00120 #Frame this data is associated with\n\
00121 # 0: no frame\n\
00122 # 1: global frame\n\
00123 string frame_id\n\
00124 \n\
00125 ================================================================================\n\
00126 MSG: geometry_msgs/Pose\n\
00127 # A representation of pose in free space, composed of postion and orientation. \n\
00128 Point position\n\
00129 Quaternion orientation\n\
00130 \n\
00131 ================================================================================\n\
00132 MSG: geometry_msgs/Point\n\
00133 # This contains the position of a point in free space\n\
00134 float64 x\n\
00135 float64 y\n\
00136 float64 z\n\
00137 \n\
00138 ================================================================================\n\
00139 MSG: geometry_msgs/Quaternion\n\
00140 # This represents an orientation in free space in quaternion form.\n\
00141 \n\
00142 float64 x\n\
00143 float64 y\n\
00144 float64 z\n\
00145 float64 w\n\
00146 \n\
00147 "; }
00148 public:
00149 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00150
00151 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00152
00153 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00154 {
00155 ros::serialization::OStream stream(write_ptr, 1000000000);
00156 ros::serialization::serialize(stream, scaled_model_id);
00157 ros::serialization::serialize(stream, ground_truth_pose);
00158 ros::serialization::serialize(stream, bagfile_location);
00159 ros::serialization::serialize(stream, scan_source);
00160 ros::serialization::serialize(stream, cloud_topic);
00161 return stream.getData();
00162 }
00163
00164 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00165 {
00166 ros::serialization::IStream stream(read_ptr, 1000000000);
00167 ros::serialization::deserialize(stream, scaled_model_id);
00168 ros::serialization::deserialize(stream, ground_truth_pose);
00169 ros::serialization::deserialize(stream, bagfile_location);
00170 ros::serialization::deserialize(stream, scan_source);
00171 ros::serialization::deserialize(stream, cloud_topic);
00172 return stream.getData();
00173 }
00174
00175 ROS_DEPRECATED virtual uint32_t serializationLength() const
00176 {
00177 uint32_t size = 0;
00178 size += ros::serialization::serializationLength(scaled_model_id);
00179 size += ros::serialization::serializationLength(ground_truth_pose);
00180 size += ros::serialization::serializationLength(bagfile_location);
00181 size += ros::serialization::serializationLength(scan_source);
00182 size += ros::serialization::serializationLength(cloud_topic);
00183 return size;
00184 }
00185
00186 typedef boost::shared_ptr< ::household_objects_database_msgs::SaveScanRequest_<ContainerAllocator> > Ptr;
00187 typedef boost::shared_ptr< ::household_objects_database_msgs::SaveScanRequest_<ContainerAllocator> const> ConstPtr;
00188 };
00189 typedef ::household_objects_database_msgs::SaveScanRequest_<std::allocator<void> > SaveScanRequest;
00190
00191 typedef boost::shared_ptr< ::household_objects_database_msgs::SaveScanRequest> SaveScanRequestPtr;
00192 typedef boost::shared_ptr< ::household_objects_database_msgs::SaveScanRequest const> SaveScanRequestConstPtr;
00193
00194
00195 template <class ContainerAllocator>
00196 struct SaveScanResponse_ : public ros::Message
00197 {
00198 typedef SaveScanResponse_<ContainerAllocator> Type;
00199
00200 SaveScanResponse_()
00201 : return_code()
00202 {
00203 }
00204
00205 SaveScanResponse_(const ContainerAllocator& _alloc)
00206 : return_code(_alloc)
00207 {
00208 }
00209
00210 typedef ::household_objects_database_msgs::DatabaseReturnCode_<ContainerAllocator> _return_code_type;
00211 ::household_objects_database_msgs::DatabaseReturnCode_<ContainerAllocator> return_code;
00212
00213
00214 private:
00215 static const char* __s_getDataType_() { return "household_objects_database_msgs/SaveScanResponse"; }
00216 public:
00217 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00218
00219 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00220
00221 private:
00222 static const char* __s_getMD5Sum_() { return "b49fccceeb56b964ed23601916a24082"; }
00223 public:
00224 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00225
00226 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00227
00228 private:
00229 static const char* __s_getServerMD5Sum_() { return "855c7b6f2658d8a9de03dd9a5f7b1f1e"; }
00230 public:
00231 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00232
00233 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00234
00235 private:
00236 static const char* __s_getMessageDefinition_() { return "\n\
00237 \n\
00238 DatabaseReturnCode return_code\n\
00239 \n\
00240 ================================================================================\n\
00241 MSG: household_objects_database_msgs/DatabaseReturnCode\n\
00242 # return codes for database-related services\n\
00243 \n\
00244 int32 UNKNOWN_ERROR = 1\n\
00245 int32 DATABASE_NOT_CONNECTED = 2\n\
00246 int32 DATABASE_QUERY_ERROR = 3\n\
00247 int32 SUCCESS = -1\n\
00248 \n\
00249 int32 code\n\
00250 "; }
00251 public:
00252 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00253
00254 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00255
00256 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00257 {
00258 ros::serialization::OStream stream(write_ptr, 1000000000);
00259 ros::serialization::serialize(stream, return_code);
00260 return stream.getData();
00261 }
00262
00263 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00264 {
00265 ros::serialization::IStream stream(read_ptr, 1000000000);
00266 ros::serialization::deserialize(stream, return_code);
00267 return stream.getData();
00268 }
00269
00270 ROS_DEPRECATED virtual uint32_t serializationLength() const
00271 {
00272 uint32_t size = 0;
00273 size += ros::serialization::serializationLength(return_code);
00274 return size;
00275 }
00276
00277 typedef boost::shared_ptr< ::household_objects_database_msgs::SaveScanResponse_<ContainerAllocator> > Ptr;
00278 typedef boost::shared_ptr< ::household_objects_database_msgs::SaveScanResponse_<ContainerAllocator> const> ConstPtr;
00279 };
00280 typedef ::household_objects_database_msgs::SaveScanResponse_<std::allocator<void> > SaveScanResponse;
00281
00282 typedef boost::shared_ptr< ::household_objects_database_msgs::SaveScanResponse> SaveScanResponsePtr;
00283 typedef boost::shared_ptr< ::household_objects_database_msgs::SaveScanResponse const> SaveScanResponseConstPtr;
00284
00285 struct SaveScan
00286 {
00287
00288 typedef SaveScanRequest Request;
00289 typedef SaveScanResponse Response;
00290 Request request;
00291 Response response;
00292
00293 typedef Request RequestType;
00294 typedef Response ResponseType;
00295 };
00296 }
00297
00298 namespace ros
00299 {
00300 namespace message_traits
00301 {
00302 template<class ContainerAllocator>
00303 struct MD5Sum< ::household_objects_database_msgs::SaveScanRequest_<ContainerAllocator> > {
00304 static const char* value()
00305 {
00306 return "492f49d320aa26325df5fb078c297fa5";
00307 }
00308
00309 static const char* value(const ::household_objects_database_msgs::SaveScanRequest_<ContainerAllocator> &) { return value(); }
00310 static const uint64_t static_value1 = 0x492f49d320aa2632ULL;
00311 static const uint64_t static_value2 = 0x5df5fb078c297fa5ULL;
00312 };
00313
00314 template<class ContainerAllocator>
00315 struct DataType< ::household_objects_database_msgs::SaveScanRequest_<ContainerAllocator> > {
00316 static const char* value()
00317 {
00318 return "household_objects_database_msgs/SaveScanRequest";
00319 }
00320
00321 static const char* value(const ::household_objects_database_msgs::SaveScanRequest_<ContainerAllocator> &) { return value(); }
00322 };
00323
00324 template<class ContainerAllocator>
00325 struct Definition< ::household_objects_database_msgs::SaveScanRequest_<ContainerAllocator> > {
00326 static const char* value()
00327 {
00328 return "\n\
00329 \n\
00330 \n\
00331 int32 scaled_model_id\n\
00332 \n\
00333 \n\
00334 geometry_msgs/PoseStamped ground_truth_pose\n\
00335 \n\
00336 \n\
00337 string bagfile_location\n\
00338 \n\
00339 \n\
00340 string scan_source\n\
00341 \n\
00342 \n\
00343 string cloud_topic\n\
00344 \n\
00345 \n\
00346 ================================================================================\n\
00347 MSG: geometry_msgs/PoseStamped\n\
00348 # A Pose with reference coordinate frame and timestamp\n\
00349 Header header\n\
00350 Pose pose\n\
00351 \n\
00352 ================================================================================\n\
00353 MSG: std_msgs/Header\n\
00354 # Standard metadata for higher-level stamped data types.\n\
00355 # This is generally used to communicate timestamped data \n\
00356 # in a particular coordinate frame.\n\
00357 # \n\
00358 # sequence ID: consecutively increasing ID \n\
00359 uint32 seq\n\
00360 #Two-integer timestamp that is expressed as:\n\
00361 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00362 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00363 # time-handling sugar is provided by the client library\n\
00364 time stamp\n\
00365 #Frame this data is associated with\n\
00366 # 0: no frame\n\
00367 # 1: global frame\n\
00368 string frame_id\n\
00369 \n\
00370 ================================================================================\n\
00371 MSG: geometry_msgs/Pose\n\
00372 # A representation of pose in free space, composed of postion and orientation. \n\
00373 Point position\n\
00374 Quaternion orientation\n\
00375 \n\
00376 ================================================================================\n\
00377 MSG: geometry_msgs/Point\n\
00378 # This contains the position of a point in free space\n\
00379 float64 x\n\
00380 float64 y\n\
00381 float64 z\n\
00382 \n\
00383 ================================================================================\n\
00384 MSG: geometry_msgs/Quaternion\n\
00385 # This represents an orientation in free space in quaternion form.\n\
00386 \n\
00387 float64 x\n\
00388 float64 y\n\
00389 float64 z\n\
00390 float64 w\n\
00391 \n\
00392 ";
00393 }
00394
00395 static const char* value(const ::household_objects_database_msgs::SaveScanRequest_<ContainerAllocator> &) { return value(); }
00396 };
00397
00398 }
00399 }
00400
00401
00402 namespace ros
00403 {
00404 namespace message_traits
00405 {
00406 template<class ContainerAllocator>
00407 struct MD5Sum< ::household_objects_database_msgs::SaveScanResponse_<ContainerAllocator> > {
00408 static const char* value()
00409 {
00410 return "b49fccceeb56b964ed23601916a24082";
00411 }
00412
00413 static const char* value(const ::household_objects_database_msgs::SaveScanResponse_<ContainerAllocator> &) { return value(); }
00414 static const uint64_t static_value1 = 0xb49fccceeb56b964ULL;
00415 static const uint64_t static_value2 = 0xed23601916a24082ULL;
00416 };
00417
00418 template<class ContainerAllocator>
00419 struct DataType< ::household_objects_database_msgs::SaveScanResponse_<ContainerAllocator> > {
00420 static const char* value()
00421 {
00422 return "household_objects_database_msgs/SaveScanResponse";
00423 }
00424
00425 static const char* value(const ::household_objects_database_msgs::SaveScanResponse_<ContainerAllocator> &) { return value(); }
00426 };
00427
00428 template<class ContainerAllocator>
00429 struct Definition< ::household_objects_database_msgs::SaveScanResponse_<ContainerAllocator> > {
00430 static const char* value()
00431 {
00432 return "\n\
00433 \n\
00434 DatabaseReturnCode return_code\n\
00435 \n\
00436 ================================================================================\n\
00437 MSG: household_objects_database_msgs/DatabaseReturnCode\n\
00438 # return codes for database-related services\n\
00439 \n\
00440 int32 UNKNOWN_ERROR = 1\n\
00441 int32 DATABASE_NOT_CONNECTED = 2\n\
00442 int32 DATABASE_QUERY_ERROR = 3\n\
00443 int32 SUCCESS = -1\n\
00444 \n\
00445 int32 code\n\
00446 ";
00447 }
00448
00449 static const char* value(const ::household_objects_database_msgs::SaveScanResponse_<ContainerAllocator> &) { return value(); }
00450 };
00451
00452 template<class ContainerAllocator> struct IsFixedSize< ::household_objects_database_msgs::SaveScanResponse_<ContainerAllocator> > : public TrueType {};
00453 }
00454 }
00455
00456 namespace ros
00457 {
00458 namespace serialization
00459 {
00460
00461 template<class ContainerAllocator> struct Serializer< ::household_objects_database_msgs::SaveScanRequest_<ContainerAllocator> >
00462 {
00463 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00464 {
00465 stream.next(m.scaled_model_id);
00466 stream.next(m.ground_truth_pose);
00467 stream.next(m.bagfile_location);
00468 stream.next(m.scan_source);
00469 stream.next(m.cloud_topic);
00470 }
00471
00472 ROS_DECLARE_ALLINONE_SERIALIZER;
00473 };
00474 }
00475 }
00476
00477
00478 namespace ros
00479 {
00480 namespace serialization
00481 {
00482
00483 template<class ContainerAllocator> struct Serializer< ::household_objects_database_msgs::SaveScanResponse_<ContainerAllocator> >
00484 {
00485 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00486 {
00487 stream.next(m.return_code);
00488 }
00489
00490 ROS_DECLARE_ALLINONE_SERIALIZER;
00491 };
00492 }
00493 }
00494
00495 namespace ros
00496 {
00497 namespace service_traits
00498 {
00499 template<>
00500 struct MD5Sum<household_objects_database_msgs::SaveScan> {
00501 static const char* value()
00502 {
00503 return "855c7b6f2658d8a9de03dd9a5f7b1f1e";
00504 }
00505
00506 static const char* value(const household_objects_database_msgs::SaveScan&) { return value(); }
00507 };
00508
00509 template<>
00510 struct DataType<household_objects_database_msgs::SaveScan> {
00511 static const char* value()
00512 {
00513 return "household_objects_database_msgs/SaveScan";
00514 }
00515
00516 static const char* value(const household_objects_database_msgs::SaveScan&) { return value(); }
00517 };
00518
00519 template<class ContainerAllocator>
00520 struct MD5Sum<household_objects_database_msgs::SaveScanRequest_<ContainerAllocator> > {
00521 static const char* value()
00522 {
00523 return "855c7b6f2658d8a9de03dd9a5f7b1f1e";
00524 }
00525
00526 static const char* value(const household_objects_database_msgs::SaveScanRequest_<ContainerAllocator> &) { return value(); }
00527 };
00528
00529 template<class ContainerAllocator>
00530 struct DataType<household_objects_database_msgs::SaveScanRequest_<ContainerAllocator> > {
00531 static const char* value()
00532 {
00533 return "household_objects_database_msgs/SaveScan";
00534 }
00535
00536 static const char* value(const household_objects_database_msgs::SaveScanRequest_<ContainerAllocator> &) { return value(); }
00537 };
00538
00539 template<class ContainerAllocator>
00540 struct MD5Sum<household_objects_database_msgs::SaveScanResponse_<ContainerAllocator> > {
00541 static const char* value()
00542 {
00543 return "855c7b6f2658d8a9de03dd9a5f7b1f1e";
00544 }
00545
00546 static const char* value(const household_objects_database_msgs::SaveScanResponse_<ContainerAllocator> &) { return value(); }
00547 };
00548
00549 template<class ContainerAllocator>
00550 struct DataType<household_objects_database_msgs::SaveScanResponse_<ContainerAllocator> > {
00551 static const char* value()
00552 {
00553 return "household_objects_database_msgs/SaveScan";
00554 }
00555
00556 static const char* value(const household_objects_database_msgs::SaveScanResponse_<ContainerAllocator> &) { return value(); }
00557 };
00558
00559 }
00560 }
00561
00562 #endif // HOUSEHOLD_OBJECTS_DATABASE_MSGS_SERVICE_SAVESCAN_H
00563