$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-tue/doc_stacks/2013-03-05_12-23-27.283047/tulip_simulator/tulip_gazebo/msg/xsens_state_message.msg */ 00002 #ifndef TULIP_GAZEBO_MESSAGE_XSENS_STATE_MESSAGE_H 00003 #define TULIP_GAZEBO_MESSAGE_XSENS_STATE_MESSAGE_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 "geometry_msgs/Pose.h" 00018 #include "geometry_msgs/Twist.h" 00019 00020 namespace tulip_gazebo 00021 { 00022 template <class ContainerAllocator> 00023 struct xsens_state_message_ { 00024 typedef xsens_state_message_<ContainerAllocator> Type; 00025 00026 xsens_state_message_() 00027 : time() 00028 , pose() 00029 , twist() 00030 { 00031 } 00032 00033 xsens_state_message_(const ContainerAllocator& _alloc) 00034 : time() 00035 , pose(_alloc) 00036 , twist(_alloc) 00037 { 00038 } 00039 00040 typedef ros::Time _time_type; 00041 ros::Time time; 00042 00043 typedef ::geometry_msgs::Pose_<ContainerAllocator> _pose_type; 00044 ::geometry_msgs::Pose_<ContainerAllocator> pose; 00045 00046 typedef ::geometry_msgs::Twist_<ContainerAllocator> _twist_type; 00047 ::geometry_msgs::Twist_<ContainerAllocator> twist; 00048 00049 00050 private: 00051 static const char* __s_getDataType_() { return "tulip_gazebo/xsens_state_message"; } 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 "07deb68b3aeac7002d1c041ea95ffeb8"; } 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 "time time\n\ 00066 geometry_msgs/Pose pose\n\ 00067 geometry_msgs/Twist twist\n\ 00068 ================================================================================\n\ 00069 MSG: geometry_msgs/Pose\n\ 00070 # A representation of pose in free space, composed of postion and orientation. \n\ 00071 Point position\n\ 00072 Quaternion orientation\n\ 00073 \n\ 00074 ================================================================================\n\ 00075 MSG: geometry_msgs/Point\n\ 00076 # This contains the position of a point in free space\n\ 00077 float64 x\n\ 00078 float64 y\n\ 00079 float64 z\n\ 00080 \n\ 00081 ================================================================================\n\ 00082 MSG: geometry_msgs/Quaternion\n\ 00083 # This represents an orientation in free space in quaternion form.\n\ 00084 \n\ 00085 float64 x\n\ 00086 float64 y\n\ 00087 float64 z\n\ 00088 float64 w\n\ 00089 \n\ 00090 ================================================================================\n\ 00091 MSG: geometry_msgs/Twist\n\ 00092 # This expresses velocity in free space broken into it's linear and angular parts. \n\ 00093 Vector3 linear\n\ 00094 Vector3 angular\n\ 00095 \n\ 00096 ================================================================================\n\ 00097 MSG: geometry_msgs/Vector3\n\ 00098 # This represents a vector in free space. \n\ 00099 \n\ 00100 float64 x\n\ 00101 float64 y\n\ 00102 float64 z\n\ 00103 "; } 00104 public: 00105 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00106 00107 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00108 00109 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00110 { 00111 ros::serialization::OStream stream(write_ptr, 1000000000); 00112 ros::serialization::serialize(stream, time); 00113 ros::serialization::serialize(stream, pose); 00114 ros::serialization::serialize(stream, twist); 00115 return stream.getData(); 00116 } 00117 00118 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00119 { 00120 ros::serialization::IStream stream(read_ptr, 1000000000); 00121 ros::serialization::deserialize(stream, time); 00122 ros::serialization::deserialize(stream, pose); 00123 ros::serialization::deserialize(stream, twist); 00124 return stream.getData(); 00125 } 00126 00127 ROS_DEPRECATED virtual uint32_t serializationLength() const 00128 { 00129 uint32_t size = 0; 00130 size += ros::serialization::serializationLength(time); 00131 size += ros::serialization::serializationLength(pose); 00132 size += ros::serialization::serializationLength(twist); 00133 return size; 00134 } 00135 00136 typedef boost::shared_ptr< ::tulip_gazebo::xsens_state_message_<ContainerAllocator> > Ptr; 00137 typedef boost::shared_ptr< ::tulip_gazebo::xsens_state_message_<ContainerAllocator> const> ConstPtr; 00138 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00139 }; // struct xsens_state_message 00140 typedef ::tulip_gazebo::xsens_state_message_<std::allocator<void> > xsens_state_message; 00141 00142 typedef boost::shared_ptr< ::tulip_gazebo::xsens_state_message> xsens_state_messagePtr; 00143 typedef boost::shared_ptr< ::tulip_gazebo::xsens_state_message const> xsens_state_messageConstPtr; 00144 00145 00146 template<typename ContainerAllocator> 00147 std::ostream& operator<<(std::ostream& s, const ::tulip_gazebo::xsens_state_message_<ContainerAllocator> & v) 00148 { 00149 ros::message_operations::Printer< ::tulip_gazebo::xsens_state_message_<ContainerAllocator> >::stream(s, "", v); 00150 return s;} 00151 00152 } // namespace tulip_gazebo 00153 00154 namespace ros 00155 { 00156 namespace message_traits 00157 { 00158 template<class ContainerAllocator> struct IsMessage< ::tulip_gazebo::xsens_state_message_<ContainerAllocator> > : public TrueType {}; 00159 template<class ContainerAllocator> struct IsMessage< ::tulip_gazebo::xsens_state_message_<ContainerAllocator> const> : public TrueType {}; 00160 template<class ContainerAllocator> 00161 struct MD5Sum< ::tulip_gazebo::xsens_state_message_<ContainerAllocator> > { 00162 static const char* value() 00163 { 00164 return "07deb68b3aeac7002d1c041ea95ffeb8"; 00165 } 00166 00167 static const char* value(const ::tulip_gazebo::xsens_state_message_<ContainerAllocator> &) { return value(); } 00168 static const uint64_t static_value1 = 0x07deb68b3aeac700ULL; 00169 static const uint64_t static_value2 = 0x2d1c041ea95ffeb8ULL; 00170 }; 00171 00172 template<class ContainerAllocator> 00173 struct DataType< ::tulip_gazebo::xsens_state_message_<ContainerAllocator> > { 00174 static const char* value() 00175 { 00176 return "tulip_gazebo/xsens_state_message"; 00177 } 00178 00179 static const char* value(const ::tulip_gazebo::xsens_state_message_<ContainerAllocator> &) { return value(); } 00180 }; 00181 00182 template<class ContainerAllocator> 00183 struct Definition< ::tulip_gazebo::xsens_state_message_<ContainerAllocator> > { 00184 static const char* value() 00185 { 00186 return "time time\n\ 00187 geometry_msgs/Pose pose\n\ 00188 geometry_msgs/Twist twist\n\ 00189 ================================================================================\n\ 00190 MSG: geometry_msgs/Pose\n\ 00191 # A representation of pose in free space, composed of postion and orientation. \n\ 00192 Point position\n\ 00193 Quaternion orientation\n\ 00194 \n\ 00195 ================================================================================\n\ 00196 MSG: geometry_msgs/Point\n\ 00197 # This contains the position of a point in free space\n\ 00198 float64 x\n\ 00199 float64 y\n\ 00200 float64 z\n\ 00201 \n\ 00202 ================================================================================\n\ 00203 MSG: geometry_msgs/Quaternion\n\ 00204 # This represents an orientation in free space in quaternion form.\n\ 00205 \n\ 00206 float64 x\n\ 00207 float64 y\n\ 00208 float64 z\n\ 00209 float64 w\n\ 00210 \n\ 00211 ================================================================================\n\ 00212 MSG: geometry_msgs/Twist\n\ 00213 # This expresses velocity in free space broken into it's linear and angular parts. \n\ 00214 Vector3 linear\n\ 00215 Vector3 angular\n\ 00216 \n\ 00217 ================================================================================\n\ 00218 MSG: geometry_msgs/Vector3\n\ 00219 # This represents a vector in free space. \n\ 00220 \n\ 00221 float64 x\n\ 00222 float64 y\n\ 00223 float64 z\n\ 00224 "; 00225 } 00226 00227 static const char* value(const ::tulip_gazebo::xsens_state_message_<ContainerAllocator> &) { return value(); } 00228 }; 00229 00230 template<class ContainerAllocator> struct IsFixedSize< ::tulip_gazebo::xsens_state_message_<ContainerAllocator> > : public TrueType {}; 00231 } // namespace message_traits 00232 } // namespace ros 00233 00234 namespace ros 00235 { 00236 namespace serialization 00237 { 00238 00239 template<class ContainerAllocator> struct Serializer< ::tulip_gazebo::xsens_state_message_<ContainerAllocator> > 00240 { 00241 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00242 { 00243 stream.next(m.time); 00244 stream.next(m.pose); 00245 stream.next(m.twist); 00246 } 00247 00248 ROS_DECLARE_ALLINONE_SERIALIZER; 00249 }; // struct xsens_state_message_ 00250 } // namespace serialization 00251 } // namespace ros 00252 00253 namespace ros 00254 { 00255 namespace message_operations 00256 { 00257 00258 template<class ContainerAllocator> 00259 struct Printer< ::tulip_gazebo::xsens_state_message_<ContainerAllocator> > 00260 { 00261 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::tulip_gazebo::xsens_state_message_<ContainerAllocator> & v) 00262 { 00263 s << indent << "time: "; 00264 Printer<ros::Time>::stream(s, indent + " ", v.time); 00265 s << indent << "pose: "; 00266 s << std::endl; 00267 Printer< ::geometry_msgs::Pose_<ContainerAllocator> >::stream(s, indent + " ", v.pose); 00268 s << indent << "twist: "; 00269 s << std::endl; 00270 Printer< ::geometry_msgs::Twist_<ContainerAllocator> >::stream(s, indent + " ", v.twist); 00271 } 00272 }; 00273 00274 00275 } // namespace message_operations 00276 } // namespace ros 00277 00278 #endif // TULIP_GAZEBO_MESSAGE_XSENS_STATE_MESSAGE_H 00279