$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-simulator_gazebo/doc_stacks/2013-03-02_13-33-37.038309/simulator_gazebo/gazebo_msgs/srv/ApplyBodyWrench.srv */ 00002 #ifndef GAZEBO_MSGS_SERVICE_APPLYBODYWRENCH_H 00003 #define GAZEBO_MSGS_SERVICE_APPLYBODYWRENCH_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/Point.h" 00020 #include "geometry_msgs/Wrench.h" 00021 00022 00023 00024 namespace gazebo_msgs 00025 { 00026 template <class ContainerAllocator> 00027 struct ApplyBodyWrenchRequest_ { 00028 typedef ApplyBodyWrenchRequest_<ContainerAllocator> Type; 00029 00030 ApplyBodyWrenchRequest_() 00031 : body_name() 00032 , reference_frame() 00033 , reference_point() 00034 , wrench() 00035 , start_time() 00036 , duration() 00037 { 00038 } 00039 00040 ApplyBodyWrenchRequest_(const ContainerAllocator& _alloc) 00041 : body_name(_alloc) 00042 , reference_frame(_alloc) 00043 , reference_point(_alloc) 00044 , wrench(_alloc) 00045 , start_time() 00046 , duration() 00047 { 00048 } 00049 00050 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _body_name_type; 00051 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > body_name; 00052 00053 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _reference_frame_type; 00054 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > reference_frame; 00055 00056 typedef ::geometry_msgs::Point_<ContainerAllocator> _reference_point_type; 00057 ::geometry_msgs::Point_<ContainerAllocator> reference_point; 00058 00059 typedef ::geometry_msgs::Wrench_<ContainerAllocator> _wrench_type; 00060 ::geometry_msgs::Wrench_<ContainerAllocator> wrench; 00061 00062 typedef ros::Time _start_time_type; 00063 ros::Time start_time; 00064 00065 typedef ros::Duration _duration_type; 00066 ros::Duration duration; 00067 00068 00069 private: 00070 static const char* __s_getDataType_() { return "gazebo_msgs/ApplyBodyWrenchRequest"; } 00071 public: 00072 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00073 00074 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00075 00076 private: 00077 static const char* __s_getMD5Sum_() { return "e37e6adf97eba5095baa77dffb71e5bd"; } 00078 public: 00079 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00080 00081 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00082 00083 private: 00084 static const char* __s_getServerMD5Sum_() { return "585b9f9618aa0581b207e2f2d90866bc"; } 00085 public: 00086 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00087 00088 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00089 00090 private: 00091 static const char* __s_getMessageDefinition_() { return "\n\ 00092 \n\ 00093 \n\ 00094 string body_name\n\ 00095 \n\ 00096 \n\ 00097 string reference_frame\n\ 00098 \n\ 00099 \n\ 00100 geometry_msgs/Point reference_point\n\ 00101 geometry_msgs/Wrench wrench\n\ 00102 time start_time\n\ 00103 \n\ 00104 \n\ 00105 duration duration\n\ 00106 \n\ 00107 \n\ 00108 \n\ 00109 \n\ 00110 \n\ 00111 ================================================================================\n\ 00112 MSG: geometry_msgs/Point\n\ 00113 # This contains the position of a point in free space\n\ 00114 float64 x\n\ 00115 float64 y\n\ 00116 float64 z\n\ 00117 \n\ 00118 ================================================================================\n\ 00119 MSG: geometry_msgs/Wrench\n\ 00120 # This represents force in free space, seperated into \n\ 00121 # it's linear and angular parts. \n\ 00122 Vector3 force\n\ 00123 Vector3 torque\n\ 00124 \n\ 00125 ================================================================================\n\ 00126 MSG: geometry_msgs/Vector3\n\ 00127 # This represents a vector in free space. \n\ 00128 \n\ 00129 float64 x\n\ 00130 float64 y\n\ 00131 float64 z\n\ 00132 "; } 00133 public: 00134 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00135 00136 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00137 00138 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00139 { 00140 ros::serialization::OStream stream(write_ptr, 1000000000); 00141 ros::serialization::serialize(stream, body_name); 00142 ros::serialization::serialize(stream, reference_frame); 00143 ros::serialization::serialize(stream, reference_point); 00144 ros::serialization::serialize(stream, wrench); 00145 ros::serialization::serialize(stream, start_time); 00146 ros::serialization::serialize(stream, duration); 00147 return stream.getData(); 00148 } 00149 00150 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00151 { 00152 ros::serialization::IStream stream(read_ptr, 1000000000); 00153 ros::serialization::deserialize(stream, body_name); 00154 ros::serialization::deserialize(stream, reference_frame); 00155 ros::serialization::deserialize(stream, reference_point); 00156 ros::serialization::deserialize(stream, wrench); 00157 ros::serialization::deserialize(stream, start_time); 00158 ros::serialization::deserialize(stream, duration); 00159 return stream.getData(); 00160 } 00161 00162 ROS_DEPRECATED virtual uint32_t serializationLength() const 00163 { 00164 uint32_t size = 0; 00165 size += ros::serialization::serializationLength(body_name); 00166 size += ros::serialization::serializationLength(reference_frame); 00167 size += ros::serialization::serializationLength(reference_point); 00168 size += ros::serialization::serializationLength(wrench); 00169 size += ros::serialization::serializationLength(start_time); 00170 size += ros::serialization::serializationLength(duration); 00171 return size; 00172 } 00173 00174 typedef boost::shared_ptr< ::gazebo_msgs::ApplyBodyWrenchRequest_<ContainerAllocator> > Ptr; 00175 typedef boost::shared_ptr< ::gazebo_msgs::ApplyBodyWrenchRequest_<ContainerAllocator> const> ConstPtr; 00176 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00177 }; // struct ApplyBodyWrenchRequest 00178 typedef ::gazebo_msgs::ApplyBodyWrenchRequest_<std::allocator<void> > ApplyBodyWrenchRequest; 00179 00180 typedef boost::shared_ptr< ::gazebo_msgs::ApplyBodyWrenchRequest> ApplyBodyWrenchRequestPtr; 00181 typedef boost::shared_ptr< ::gazebo_msgs::ApplyBodyWrenchRequest const> ApplyBodyWrenchRequestConstPtr; 00182 00183 00184 template <class ContainerAllocator> 00185 struct ApplyBodyWrenchResponse_ { 00186 typedef ApplyBodyWrenchResponse_<ContainerAllocator> Type; 00187 00188 ApplyBodyWrenchResponse_() 00189 : success(false) 00190 , status_message() 00191 { 00192 } 00193 00194 ApplyBodyWrenchResponse_(const ContainerAllocator& _alloc) 00195 : success(false) 00196 , status_message(_alloc) 00197 { 00198 } 00199 00200 typedef uint8_t _success_type; 00201 uint8_t success; 00202 00203 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _status_message_type; 00204 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > status_message; 00205 00206 00207 private: 00208 static const char* __s_getDataType_() { return "gazebo_msgs/ApplyBodyWrenchResponse"; } 00209 public: 00210 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00211 00212 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00213 00214 private: 00215 static const char* __s_getMD5Sum_() { return "2ec6f3eff0161f4257b808b12bc830c2"; } 00216 public: 00217 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00218 00219 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00220 00221 private: 00222 static const char* __s_getServerMD5Sum_() { return "585b9f9618aa0581b207e2f2d90866bc"; } 00223 public: 00224 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00225 00226 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00227 00228 private: 00229 static const char* __s_getMessageDefinition_() { return "bool success\n\ 00230 string status_message\n\ 00231 \n\ 00232 \n\ 00233 "; } 00234 public: 00235 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00236 00237 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00238 00239 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00240 { 00241 ros::serialization::OStream stream(write_ptr, 1000000000); 00242 ros::serialization::serialize(stream, success); 00243 ros::serialization::serialize(stream, status_message); 00244 return stream.getData(); 00245 } 00246 00247 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00248 { 00249 ros::serialization::IStream stream(read_ptr, 1000000000); 00250 ros::serialization::deserialize(stream, success); 00251 ros::serialization::deserialize(stream, status_message); 00252 return stream.getData(); 00253 } 00254 00255 ROS_DEPRECATED virtual uint32_t serializationLength() const 00256 { 00257 uint32_t size = 0; 00258 size += ros::serialization::serializationLength(success); 00259 size += ros::serialization::serializationLength(status_message); 00260 return size; 00261 } 00262 00263 typedef boost::shared_ptr< ::gazebo_msgs::ApplyBodyWrenchResponse_<ContainerAllocator> > Ptr; 00264 typedef boost::shared_ptr< ::gazebo_msgs::ApplyBodyWrenchResponse_<ContainerAllocator> const> ConstPtr; 00265 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00266 }; // struct ApplyBodyWrenchResponse 00267 typedef ::gazebo_msgs::ApplyBodyWrenchResponse_<std::allocator<void> > ApplyBodyWrenchResponse; 00268 00269 typedef boost::shared_ptr< ::gazebo_msgs::ApplyBodyWrenchResponse> ApplyBodyWrenchResponsePtr; 00270 typedef boost::shared_ptr< ::gazebo_msgs::ApplyBodyWrenchResponse const> ApplyBodyWrenchResponseConstPtr; 00271 00272 struct ApplyBodyWrench 00273 { 00274 00275 typedef ApplyBodyWrenchRequest Request; 00276 typedef ApplyBodyWrenchResponse Response; 00277 Request request; 00278 Response response; 00279 00280 typedef Request RequestType; 00281 typedef Response ResponseType; 00282 }; // struct ApplyBodyWrench 00283 } // namespace gazebo_msgs 00284 00285 namespace ros 00286 { 00287 namespace message_traits 00288 { 00289 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::ApplyBodyWrenchRequest_<ContainerAllocator> > : public TrueType {}; 00290 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::ApplyBodyWrenchRequest_<ContainerAllocator> const> : public TrueType {}; 00291 template<class ContainerAllocator> 00292 struct MD5Sum< ::gazebo_msgs::ApplyBodyWrenchRequest_<ContainerAllocator> > { 00293 static const char* value() 00294 { 00295 return "e37e6adf97eba5095baa77dffb71e5bd"; 00296 } 00297 00298 static const char* value(const ::gazebo_msgs::ApplyBodyWrenchRequest_<ContainerAllocator> &) { return value(); } 00299 static const uint64_t static_value1 = 0xe37e6adf97eba509ULL; 00300 static const uint64_t static_value2 = 0x5baa77dffb71e5bdULL; 00301 }; 00302 00303 template<class ContainerAllocator> 00304 struct DataType< ::gazebo_msgs::ApplyBodyWrenchRequest_<ContainerAllocator> > { 00305 static const char* value() 00306 { 00307 return "gazebo_msgs/ApplyBodyWrenchRequest"; 00308 } 00309 00310 static const char* value(const ::gazebo_msgs::ApplyBodyWrenchRequest_<ContainerAllocator> &) { return value(); } 00311 }; 00312 00313 template<class ContainerAllocator> 00314 struct Definition< ::gazebo_msgs::ApplyBodyWrenchRequest_<ContainerAllocator> > { 00315 static const char* value() 00316 { 00317 return "\n\ 00318 \n\ 00319 \n\ 00320 string body_name\n\ 00321 \n\ 00322 \n\ 00323 string reference_frame\n\ 00324 \n\ 00325 \n\ 00326 geometry_msgs/Point reference_point\n\ 00327 geometry_msgs/Wrench wrench\n\ 00328 time start_time\n\ 00329 \n\ 00330 \n\ 00331 duration duration\n\ 00332 \n\ 00333 \n\ 00334 \n\ 00335 \n\ 00336 \n\ 00337 ================================================================================\n\ 00338 MSG: geometry_msgs/Point\n\ 00339 # This contains the position of a point in free space\n\ 00340 float64 x\n\ 00341 float64 y\n\ 00342 float64 z\n\ 00343 \n\ 00344 ================================================================================\n\ 00345 MSG: geometry_msgs/Wrench\n\ 00346 # This represents force in free space, seperated into \n\ 00347 # it's linear and angular parts. \n\ 00348 Vector3 force\n\ 00349 Vector3 torque\n\ 00350 \n\ 00351 ================================================================================\n\ 00352 MSG: geometry_msgs/Vector3\n\ 00353 # This represents a vector in free space. \n\ 00354 \n\ 00355 float64 x\n\ 00356 float64 y\n\ 00357 float64 z\n\ 00358 "; 00359 } 00360 00361 static const char* value(const ::gazebo_msgs::ApplyBodyWrenchRequest_<ContainerAllocator> &) { return value(); } 00362 }; 00363 00364 } // namespace message_traits 00365 } // namespace ros 00366 00367 00368 namespace ros 00369 { 00370 namespace message_traits 00371 { 00372 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::ApplyBodyWrenchResponse_<ContainerAllocator> > : public TrueType {}; 00373 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::ApplyBodyWrenchResponse_<ContainerAllocator> const> : public TrueType {}; 00374 template<class ContainerAllocator> 00375 struct MD5Sum< ::gazebo_msgs::ApplyBodyWrenchResponse_<ContainerAllocator> > { 00376 static const char* value() 00377 { 00378 return "2ec6f3eff0161f4257b808b12bc830c2"; 00379 } 00380 00381 static const char* value(const ::gazebo_msgs::ApplyBodyWrenchResponse_<ContainerAllocator> &) { return value(); } 00382 static const uint64_t static_value1 = 0x2ec6f3eff0161f42ULL; 00383 static const uint64_t static_value2 = 0x57b808b12bc830c2ULL; 00384 }; 00385 00386 template<class ContainerAllocator> 00387 struct DataType< ::gazebo_msgs::ApplyBodyWrenchResponse_<ContainerAllocator> > { 00388 static const char* value() 00389 { 00390 return "gazebo_msgs/ApplyBodyWrenchResponse"; 00391 } 00392 00393 static const char* value(const ::gazebo_msgs::ApplyBodyWrenchResponse_<ContainerAllocator> &) { return value(); } 00394 }; 00395 00396 template<class ContainerAllocator> 00397 struct Definition< ::gazebo_msgs::ApplyBodyWrenchResponse_<ContainerAllocator> > { 00398 static const char* value() 00399 { 00400 return "bool success\n\ 00401 string status_message\n\ 00402 \n\ 00403 \n\ 00404 "; 00405 } 00406 00407 static const char* value(const ::gazebo_msgs::ApplyBodyWrenchResponse_<ContainerAllocator> &) { return value(); } 00408 }; 00409 00410 } // namespace message_traits 00411 } // namespace ros 00412 00413 namespace ros 00414 { 00415 namespace serialization 00416 { 00417 00418 template<class ContainerAllocator> struct Serializer< ::gazebo_msgs::ApplyBodyWrenchRequest_<ContainerAllocator> > 00419 { 00420 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00421 { 00422 stream.next(m.body_name); 00423 stream.next(m.reference_frame); 00424 stream.next(m.reference_point); 00425 stream.next(m.wrench); 00426 stream.next(m.start_time); 00427 stream.next(m.duration); 00428 } 00429 00430 ROS_DECLARE_ALLINONE_SERIALIZER; 00431 }; // struct ApplyBodyWrenchRequest_ 00432 } // namespace serialization 00433 } // namespace ros 00434 00435 00436 namespace ros 00437 { 00438 namespace serialization 00439 { 00440 00441 template<class ContainerAllocator> struct Serializer< ::gazebo_msgs::ApplyBodyWrenchResponse_<ContainerAllocator> > 00442 { 00443 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00444 { 00445 stream.next(m.success); 00446 stream.next(m.status_message); 00447 } 00448 00449 ROS_DECLARE_ALLINONE_SERIALIZER; 00450 }; // struct ApplyBodyWrenchResponse_ 00451 } // namespace serialization 00452 } // namespace ros 00453 00454 namespace ros 00455 { 00456 namespace service_traits 00457 { 00458 template<> 00459 struct MD5Sum<gazebo_msgs::ApplyBodyWrench> { 00460 static const char* value() 00461 { 00462 return "585b9f9618aa0581b207e2f2d90866bc"; 00463 } 00464 00465 static const char* value(const gazebo_msgs::ApplyBodyWrench&) { return value(); } 00466 }; 00467 00468 template<> 00469 struct DataType<gazebo_msgs::ApplyBodyWrench> { 00470 static const char* value() 00471 { 00472 return "gazebo_msgs/ApplyBodyWrench"; 00473 } 00474 00475 static const char* value(const gazebo_msgs::ApplyBodyWrench&) { return value(); } 00476 }; 00477 00478 template<class ContainerAllocator> 00479 struct MD5Sum<gazebo_msgs::ApplyBodyWrenchRequest_<ContainerAllocator> > { 00480 static const char* value() 00481 { 00482 return "585b9f9618aa0581b207e2f2d90866bc"; 00483 } 00484 00485 static const char* value(const gazebo_msgs::ApplyBodyWrenchRequest_<ContainerAllocator> &) { return value(); } 00486 }; 00487 00488 template<class ContainerAllocator> 00489 struct DataType<gazebo_msgs::ApplyBodyWrenchRequest_<ContainerAllocator> > { 00490 static const char* value() 00491 { 00492 return "gazebo_msgs/ApplyBodyWrench"; 00493 } 00494 00495 static const char* value(const gazebo_msgs::ApplyBodyWrenchRequest_<ContainerAllocator> &) { return value(); } 00496 }; 00497 00498 template<class ContainerAllocator> 00499 struct MD5Sum<gazebo_msgs::ApplyBodyWrenchResponse_<ContainerAllocator> > { 00500 static const char* value() 00501 { 00502 return "585b9f9618aa0581b207e2f2d90866bc"; 00503 } 00504 00505 static const char* value(const gazebo_msgs::ApplyBodyWrenchResponse_<ContainerAllocator> &) { return value(); } 00506 }; 00507 00508 template<class ContainerAllocator> 00509 struct DataType<gazebo_msgs::ApplyBodyWrenchResponse_<ContainerAllocator> > { 00510 static const char* value() 00511 { 00512 return "gazebo_msgs/ApplyBodyWrench"; 00513 } 00514 00515 static const char* value(const gazebo_msgs::ApplyBodyWrenchResponse_<ContainerAllocator> &) { return value(); } 00516 }; 00517 00518 } // namespace service_traits 00519 } // namespace ros 00520 00521 #endif // GAZEBO_MSGS_SERVICE_APPLYBODYWRENCH_H 00522