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