$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-common_msgs/doc_stacks/2013-03-01_14-58-52.505545/common_msgs/geometry_msgs/msg/TransformStamped.msg */ 00002 #ifndef GEOMETRY_MSGS_MESSAGE_TRANSFORMSTAMPED_H 00003 #define GEOMETRY_MSGS_MESSAGE_TRANSFORMSTAMPED_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 "std_msgs/Header.h" 00018 #include "geometry_msgs/Transform.h" 00019 00020 namespace geometry_msgs 00021 { 00022 template <class ContainerAllocator> 00023 struct TransformStamped_ { 00024 typedef TransformStamped_<ContainerAllocator> Type; 00025 00026 TransformStamped_() 00027 : header() 00028 , child_frame_id() 00029 , transform() 00030 { 00031 } 00032 00033 TransformStamped_(const ContainerAllocator& _alloc) 00034 : header(_alloc) 00035 , child_frame_id(_alloc) 00036 , transform(_alloc) 00037 { 00038 } 00039 00040 typedef ::std_msgs::Header_<ContainerAllocator> _header_type; 00041 ::std_msgs::Header_<ContainerAllocator> header; 00042 00043 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _child_frame_id_type; 00044 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > child_frame_id; 00045 00046 typedef ::geometry_msgs::Transform_<ContainerAllocator> _transform_type; 00047 ::geometry_msgs::Transform_<ContainerAllocator> transform; 00048 00049 00050 private: 00051 static const char* __s_getDataType_() { return "geometry_msgs/TransformStamped"; } 00052 public: 00053 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00054 00055 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00056 00057 private: 00058 static const char* __s_getMD5Sum_() { return "b5764a33bfeb3588febc2682852579b0"; } 00059 public: 00060 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00061 00062 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00063 00064 private: 00065 static const char* __s_getMessageDefinition_() { return "# This expresses a transform from coordinate frame header.frame_id\n\ 00066 # to the coordinate frame child_frame_id\n\ 00067 #\n\ 00068 # This message is mostly used by the \n\ 00069 # <a href=\"http://www.ros.org/wiki/tf\">tf</a> package. \n\ 00070 # See it's documentation for more information.\n\ 00071 \n\ 00072 Header header\n\ 00073 string child_frame_id # the frame id of the child frame\n\ 00074 Transform transform\n\ 00075 \n\ 00076 ================================================================================\n\ 00077 MSG: std_msgs/Header\n\ 00078 # Standard metadata for higher-level stamped data types.\n\ 00079 # This is generally used to communicate timestamped data \n\ 00080 # in a particular coordinate frame.\n\ 00081 # \n\ 00082 # sequence ID: consecutively increasing ID \n\ 00083 uint32 seq\n\ 00084 #Two-integer timestamp that is expressed as:\n\ 00085 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00086 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00087 # time-handling sugar is provided by the client library\n\ 00088 time stamp\n\ 00089 #Frame this data is associated with\n\ 00090 # 0: no frame\n\ 00091 # 1: global frame\n\ 00092 string frame_id\n\ 00093 \n\ 00094 ================================================================================\n\ 00095 MSG: geometry_msgs/Transform\n\ 00096 # This represents the transform between two coordinate frames in free space.\n\ 00097 \n\ 00098 Vector3 translation\n\ 00099 Quaternion rotation\n\ 00100 \n\ 00101 ================================================================================\n\ 00102 MSG: geometry_msgs/Vector3\n\ 00103 # This represents a vector in free space. \n\ 00104 \n\ 00105 float64 x\n\ 00106 float64 y\n\ 00107 float64 z\n\ 00108 ================================================================================\n\ 00109 MSG: geometry_msgs/Quaternion\n\ 00110 # This represents an orientation in free space in quaternion form.\n\ 00111 \n\ 00112 float64 x\n\ 00113 float64 y\n\ 00114 float64 z\n\ 00115 float64 w\n\ 00116 \n\ 00117 "; } 00118 public: 00119 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00120 00121 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00122 00123 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00124 { 00125 ros::serialization::OStream stream(write_ptr, 1000000000); 00126 ros::serialization::serialize(stream, header); 00127 ros::serialization::serialize(stream, child_frame_id); 00128 ros::serialization::serialize(stream, transform); 00129 return stream.getData(); 00130 } 00131 00132 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00133 { 00134 ros::serialization::IStream stream(read_ptr, 1000000000); 00135 ros::serialization::deserialize(stream, header); 00136 ros::serialization::deserialize(stream, child_frame_id); 00137 ros::serialization::deserialize(stream, transform); 00138 return stream.getData(); 00139 } 00140 00141 ROS_DEPRECATED virtual uint32_t serializationLength() const 00142 { 00143 uint32_t size = 0; 00144 size += ros::serialization::serializationLength(header); 00145 size += ros::serialization::serializationLength(child_frame_id); 00146 size += ros::serialization::serializationLength(transform); 00147 return size; 00148 } 00149 00150 typedef boost::shared_ptr< ::geometry_msgs::TransformStamped_<ContainerAllocator> > Ptr; 00151 typedef boost::shared_ptr< ::geometry_msgs::TransformStamped_<ContainerAllocator> const> ConstPtr; 00152 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00153 }; // struct TransformStamped 00154 typedef ::geometry_msgs::TransformStamped_<std::allocator<void> > TransformStamped; 00155 00156 typedef boost::shared_ptr< ::geometry_msgs::TransformStamped> TransformStampedPtr; 00157 typedef boost::shared_ptr< ::geometry_msgs::TransformStamped const> TransformStampedConstPtr; 00158 00159 00160 template<typename ContainerAllocator> 00161 std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::TransformStamped_<ContainerAllocator> & v) 00162 { 00163 ros::message_operations::Printer< ::geometry_msgs::TransformStamped_<ContainerAllocator> >::stream(s, "", v); 00164 return s;} 00165 00166 } // namespace geometry_msgs 00167 00168 namespace ros 00169 { 00170 namespace message_traits 00171 { 00172 template<class ContainerAllocator> struct IsMessage< ::geometry_msgs::TransformStamped_<ContainerAllocator> > : public TrueType {}; 00173 template<class ContainerAllocator> struct IsMessage< ::geometry_msgs::TransformStamped_<ContainerAllocator> const> : public TrueType {}; 00174 template<class ContainerAllocator> 00175 struct MD5Sum< ::geometry_msgs::TransformStamped_<ContainerAllocator> > { 00176 static const char* value() 00177 { 00178 return "b5764a33bfeb3588febc2682852579b0"; 00179 } 00180 00181 static const char* value(const ::geometry_msgs::TransformStamped_<ContainerAllocator> &) { return value(); } 00182 static const uint64_t static_value1 = 0xb5764a33bfeb3588ULL; 00183 static const uint64_t static_value2 = 0xfebc2682852579b0ULL; 00184 }; 00185 00186 template<class ContainerAllocator> 00187 struct DataType< ::geometry_msgs::TransformStamped_<ContainerAllocator> > { 00188 static const char* value() 00189 { 00190 return "geometry_msgs/TransformStamped"; 00191 } 00192 00193 static const char* value(const ::geometry_msgs::TransformStamped_<ContainerAllocator> &) { return value(); } 00194 }; 00195 00196 template<class ContainerAllocator> 00197 struct Definition< ::geometry_msgs::TransformStamped_<ContainerAllocator> > { 00198 static const char* value() 00199 { 00200 return "# This expresses a transform from coordinate frame header.frame_id\n\ 00201 # to the coordinate frame child_frame_id\n\ 00202 #\n\ 00203 # This message is mostly used by the \n\ 00204 # <a href=\"http://www.ros.org/wiki/tf\">tf</a> package. \n\ 00205 # See it's documentation for more information.\n\ 00206 \n\ 00207 Header header\n\ 00208 string child_frame_id # the frame id of the child frame\n\ 00209 Transform transform\n\ 00210 \n\ 00211 ================================================================================\n\ 00212 MSG: std_msgs/Header\n\ 00213 # Standard metadata for higher-level stamped data types.\n\ 00214 # This is generally used to communicate timestamped data \n\ 00215 # in a particular coordinate frame.\n\ 00216 # \n\ 00217 # sequence ID: consecutively increasing ID \n\ 00218 uint32 seq\n\ 00219 #Two-integer timestamp that is expressed as:\n\ 00220 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00221 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00222 # time-handling sugar is provided by the client library\n\ 00223 time stamp\n\ 00224 #Frame this data is associated with\n\ 00225 # 0: no frame\n\ 00226 # 1: global frame\n\ 00227 string frame_id\n\ 00228 \n\ 00229 ================================================================================\n\ 00230 MSG: geometry_msgs/Transform\n\ 00231 # This represents the transform between two coordinate frames in free space.\n\ 00232 \n\ 00233 Vector3 translation\n\ 00234 Quaternion rotation\n\ 00235 \n\ 00236 ================================================================================\n\ 00237 MSG: geometry_msgs/Vector3\n\ 00238 # This represents a vector in free space. \n\ 00239 \n\ 00240 float64 x\n\ 00241 float64 y\n\ 00242 float64 z\n\ 00243 ================================================================================\n\ 00244 MSG: geometry_msgs/Quaternion\n\ 00245 # This represents an orientation in free space in quaternion form.\n\ 00246 \n\ 00247 float64 x\n\ 00248 float64 y\n\ 00249 float64 z\n\ 00250 float64 w\n\ 00251 \n\ 00252 "; 00253 } 00254 00255 static const char* value(const ::geometry_msgs::TransformStamped_<ContainerAllocator> &) { return value(); } 00256 }; 00257 00258 template<class ContainerAllocator> struct HasHeader< ::geometry_msgs::TransformStamped_<ContainerAllocator> > : public TrueType {}; 00259 template<class ContainerAllocator> struct HasHeader< const ::geometry_msgs::TransformStamped_<ContainerAllocator> > : public TrueType {}; 00260 } // namespace message_traits 00261 } // namespace ros 00262 00263 namespace ros 00264 { 00265 namespace serialization 00266 { 00267 00268 template<class ContainerAllocator> struct Serializer< ::geometry_msgs::TransformStamped_<ContainerAllocator> > 00269 { 00270 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00271 { 00272 stream.next(m.header); 00273 stream.next(m.child_frame_id); 00274 stream.next(m.transform); 00275 } 00276 00277 ROS_DECLARE_ALLINONE_SERIALIZER; 00278 }; // struct TransformStamped_ 00279 } // namespace serialization 00280 } // namespace ros 00281 00282 namespace ros 00283 { 00284 namespace message_operations 00285 { 00286 00287 template<class ContainerAllocator> 00288 struct Printer< ::geometry_msgs::TransformStamped_<ContainerAllocator> > 00289 { 00290 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::TransformStamped_<ContainerAllocator> & v) 00291 { 00292 s << indent << "header: "; 00293 s << std::endl; 00294 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header); 00295 s << indent << "child_frame_id: "; 00296 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.child_frame_id); 00297 s << indent << "transform: "; 00298 s << std::endl; 00299 Printer< ::geometry_msgs::Transform_<ContainerAllocator> >::stream(s, indent + " ", v.transform); 00300 } 00301 }; 00302 00303 00304 } // namespace message_operations 00305 } // namespace ros 00306 00307 #endif // GEOMETRY_MSGS_MESSAGE_TRANSFORMSTAMPED_H 00308