$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-asctec_drivers/doc_stacks/2013-03-05_11-30-36.379198/asctec_drivers/asctec_msgs/msg/IMURawData.msg */ 00002 #ifndef ASCTEC_MSGS_MESSAGE_IMURAWDATA_H 00003 #define ASCTEC_MSGS_MESSAGE_IMURAWDATA_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 00019 namespace asctec_msgs 00020 { 00021 template <class ContainerAllocator> 00022 struct IMURawData_ { 00023 typedef IMURawData_<ContainerAllocator> Type; 00024 00025 IMURawData_() 00026 : header() 00027 , pressure(0) 00028 , gyro_x(0) 00029 , gyro_y(0) 00030 , gyro_z(0) 00031 , mag_x(0) 00032 , mag_y(0) 00033 , mag_z(0) 00034 , acc_x(0) 00035 , acc_y(0) 00036 , acc_z(0) 00037 , temp_gyro(0) 00038 , temp_ADC(0) 00039 { 00040 } 00041 00042 IMURawData_(const ContainerAllocator& _alloc) 00043 : header(_alloc) 00044 , pressure(0) 00045 , gyro_x(0) 00046 , gyro_y(0) 00047 , gyro_z(0) 00048 , mag_x(0) 00049 , mag_y(0) 00050 , mag_z(0) 00051 , acc_x(0) 00052 , acc_y(0) 00053 , acc_z(0) 00054 , temp_gyro(0) 00055 , temp_ADC(0) 00056 { 00057 } 00058 00059 typedef ::std_msgs::Header_<ContainerAllocator> _header_type; 00060 ::std_msgs::Header_<ContainerAllocator> header; 00061 00062 typedef int32_t _pressure_type; 00063 int32_t pressure; 00064 00065 typedef int16_t _gyro_x_type; 00066 int16_t gyro_x; 00067 00068 typedef int16_t _gyro_y_type; 00069 int16_t gyro_y; 00070 00071 typedef int16_t _gyro_z_type; 00072 int16_t gyro_z; 00073 00074 typedef int16_t _mag_x_type; 00075 int16_t mag_x; 00076 00077 typedef int16_t _mag_y_type; 00078 int16_t mag_y; 00079 00080 typedef int16_t _mag_z_type; 00081 int16_t mag_z; 00082 00083 typedef int16_t _acc_x_type; 00084 int16_t acc_x; 00085 00086 typedef int16_t _acc_y_type; 00087 int16_t acc_y; 00088 00089 typedef int16_t _acc_z_type; 00090 int16_t acc_z; 00091 00092 typedef int16_t _temp_gyro_type; 00093 int16_t temp_gyro; 00094 00095 typedef int32_t _temp_ADC_type; 00096 int32_t temp_ADC; 00097 00098 00099 private: 00100 static const char* __s_getDataType_() { return "asctec_msgs/IMURawData"; } 00101 public: 00102 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00103 00104 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00105 00106 private: 00107 static const char* __s_getMD5Sum_() { return "2cfd4b9ba0bc72be7f937c948d990cd9"; } 00108 public: 00109 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00110 00111 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00112 00113 private: 00114 static const char* __s_getMessageDefinition_() { return "# Software License Agreement (BSD License)\n\ 00115 #\n\ 00116 # Copyright (c) 2010\n\ 00117 # William Morris <morris@ee.ccny.cuny.edu>\n\ 00118 # Ivan Dryanovski <ivan.dryanovski@gmail.com>\n\ 00119 # All rights reserved.\n\ 00120 #\n\ 00121 # Redistribution and use in source and binary forms, with or without\n\ 00122 # modification, are permitted provided that the following conditions\n\ 00123 # are met:\n\ 00124 #\n\ 00125 # * Redistributions of source code must retain the above copyright\n\ 00126 # notice, this list of conditions and the following disclaimer.\n\ 00127 # * Redistributions in binary form must reproduce the above\n\ 00128 # copyright notice, this list of conditions and the following\n\ 00129 # disclaimer in the documentation and/or other materials provided\n\ 00130 # with the distribution.\n\ 00131 # * Neither the name of CCNY Robotics Lab nor the names of its\n\ 00132 # contributors may be used to endorse or promote products derived\n\ 00133 # from this software without specific prior written permission.\n\ 00134 #\n\ 00135 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n\ 00136 # \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n\ 00137 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n\ 00138 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n\ 00139 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n\ 00140 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n\ 00141 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n\ 00142 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n\ 00143 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n\ 00144 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n\ 00145 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n\ 00146 # POSSIBILITY OF SUCH DAMAGE.\n\ 00147 \n\ 00148 Header header\n\ 00149 #pressure sensor 24-bit value, not scaled but bias free\n\ 00150 int32 pressure\n\ 00151 \n\ 00152 #16-bit gyro readings; 32768 = 2.5V\n\ 00153 int16 gyro_x\n\ 00154 int16 gyro_y\n\ 00155 int16 gyro_z\n\ 00156 \n\ 00157 #10-bit magnetic field sensor readings\n\ 00158 int16 mag_x\n\ 00159 int16 mag_y\n\ 00160 int16 mag_z\n\ 00161 \n\ 00162 #16-bit accelerometer readings\n\ 00163 int16 acc_x\n\ 00164 int16 acc_y\n\ 00165 int16 acc_z\n\ 00166 \n\ 00167 #16-bit temperature measurement using yaw-gyro internal sensor\n\ 00168 int16 temp_gyro\n\ 00169 \n\ 00170 #16-bit temperature measurement using ADC internal sensor\n\ 00171 int32 temp_ADC\n\ 00172 \n\ 00173 ================================================================================\n\ 00174 MSG: std_msgs/Header\n\ 00175 # Standard metadata for higher-level stamped data types.\n\ 00176 # This is generally used to communicate timestamped data \n\ 00177 # in a particular coordinate frame.\n\ 00178 # \n\ 00179 # sequence ID: consecutively increasing ID \n\ 00180 uint32 seq\n\ 00181 #Two-integer timestamp that is expressed as:\n\ 00182 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00183 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00184 # time-handling sugar is provided by the client library\n\ 00185 time stamp\n\ 00186 #Frame this data is associated with\n\ 00187 # 0: no frame\n\ 00188 # 1: global frame\n\ 00189 string frame_id\n\ 00190 \n\ 00191 "; } 00192 public: 00193 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00194 00195 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00196 00197 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00198 { 00199 ros::serialization::OStream stream(write_ptr, 1000000000); 00200 ros::serialization::serialize(stream, header); 00201 ros::serialization::serialize(stream, pressure); 00202 ros::serialization::serialize(stream, gyro_x); 00203 ros::serialization::serialize(stream, gyro_y); 00204 ros::serialization::serialize(stream, gyro_z); 00205 ros::serialization::serialize(stream, mag_x); 00206 ros::serialization::serialize(stream, mag_y); 00207 ros::serialization::serialize(stream, mag_z); 00208 ros::serialization::serialize(stream, acc_x); 00209 ros::serialization::serialize(stream, acc_y); 00210 ros::serialization::serialize(stream, acc_z); 00211 ros::serialization::serialize(stream, temp_gyro); 00212 ros::serialization::serialize(stream, temp_ADC); 00213 return stream.getData(); 00214 } 00215 00216 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00217 { 00218 ros::serialization::IStream stream(read_ptr, 1000000000); 00219 ros::serialization::deserialize(stream, header); 00220 ros::serialization::deserialize(stream, pressure); 00221 ros::serialization::deserialize(stream, gyro_x); 00222 ros::serialization::deserialize(stream, gyro_y); 00223 ros::serialization::deserialize(stream, gyro_z); 00224 ros::serialization::deserialize(stream, mag_x); 00225 ros::serialization::deserialize(stream, mag_y); 00226 ros::serialization::deserialize(stream, mag_z); 00227 ros::serialization::deserialize(stream, acc_x); 00228 ros::serialization::deserialize(stream, acc_y); 00229 ros::serialization::deserialize(stream, acc_z); 00230 ros::serialization::deserialize(stream, temp_gyro); 00231 ros::serialization::deserialize(stream, temp_ADC); 00232 return stream.getData(); 00233 } 00234 00235 ROS_DEPRECATED virtual uint32_t serializationLength() const 00236 { 00237 uint32_t size = 0; 00238 size += ros::serialization::serializationLength(header); 00239 size += ros::serialization::serializationLength(pressure); 00240 size += ros::serialization::serializationLength(gyro_x); 00241 size += ros::serialization::serializationLength(gyro_y); 00242 size += ros::serialization::serializationLength(gyro_z); 00243 size += ros::serialization::serializationLength(mag_x); 00244 size += ros::serialization::serializationLength(mag_y); 00245 size += ros::serialization::serializationLength(mag_z); 00246 size += ros::serialization::serializationLength(acc_x); 00247 size += ros::serialization::serializationLength(acc_y); 00248 size += ros::serialization::serializationLength(acc_z); 00249 size += ros::serialization::serializationLength(temp_gyro); 00250 size += ros::serialization::serializationLength(temp_ADC); 00251 return size; 00252 } 00253 00254 typedef boost::shared_ptr< ::asctec_msgs::IMURawData_<ContainerAllocator> > Ptr; 00255 typedef boost::shared_ptr< ::asctec_msgs::IMURawData_<ContainerAllocator> const> ConstPtr; 00256 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00257 }; // struct IMURawData 00258 typedef ::asctec_msgs::IMURawData_<std::allocator<void> > IMURawData; 00259 00260 typedef boost::shared_ptr< ::asctec_msgs::IMURawData> IMURawDataPtr; 00261 typedef boost::shared_ptr< ::asctec_msgs::IMURawData const> IMURawDataConstPtr; 00262 00263 00264 template<typename ContainerAllocator> 00265 std::ostream& operator<<(std::ostream& s, const ::asctec_msgs::IMURawData_<ContainerAllocator> & v) 00266 { 00267 ros::message_operations::Printer< ::asctec_msgs::IMURawData_<ContainerAllocator> >::stream(s, "", v); 00268 return s;} 00269 00270 } // namespace asctec_msgs 00271 00272 namespace ros 00273 { 00274 namespace message_traits 00275 { 00276 template<class ContainerAllocator> struct IsMessage< ::asctec_msgs::IMURawData_<ContainerAllocator> > : public TrueType {}; 00277 template<class ContainerAllocator> struct IsMessage< ::asctec_msgs::IMURawData_<ContainerAllocator> const> : public TrueType {}; 00278 template<class ContainerAllocator> 00279 struct MD5Sum< ::asctec_msgs::IMURawData_<ContainerAllocator> > { 00280 static const char* value() 00281 { 00282 return "2cfd4b9ba0bc72be7f937c948d990cd9"; 00283 } 00284 00285 static const char* value(const ::asctec_msgs::IMURawData_<ContainerAllocator> &) { return value(); } 00286 static const uint64_t static_value1 = 0x2cfd4b9ba0bc72beULL; 00287 static const uint64_t static_value2 = 0x7f937c948d990cd9ULL; 00288 }; 00289 00290 template<class ContainerAllocator> 00291 struct DataType< ::asctec_msgs::IMURawData_<ContainerAllocator> > { 00292 static const char* value() 00293 { 00294 return "asctec_msgs/IMURawData"; 00295 } 00296 00297 static const char* value(const ::asctec_msgs::IMURawData_<ContainerAllocator> &) { return value(); } 00298 }; 00299 00300 template<class ContainerAllocator> 00301 struct Definition< ::asctec_msgs::IMURawData_<ContainerAllocator> > { 00302 static const char* value() 00303 { 00304 return "# Software License Agreement (BSD License)\n\ 00305 #\n\ 00306 # Copyright (c) 2010\n\ 00307 # William Morris <morris@ee.ccny.cuny.edu>\n\ 00308 # Ivan Dryanovski <ivan.dryanovski@gmail.com>\n\ 00309 # All rights reserved.\n\ 00310 #\n\ 00311 # Redistribution and use in source and binary forms, with or without\n\ 00312 # modification, are permitted provided that the following conditions\n\ 00313 # are met:\n\ 00314 #\n\ 00315 # * Redistributions of source code must retain the above copyright\n\ 00316 # notice, this list of conditions and the following disclaimer.\n\ 00317 # * Redistributions in binary form must reproduce the above\n\ 00318 # copyright notice, this list of conditions and the following\n\ 00319 # disclaimer in the documentation and/or other materials provided\n\ 00320 # with the distribution.\n\ 00321 # * Neither the name of CCNY Robotics Lab nor the names of its\n\ 00322 # contributors may be used to endorse or promote products derived\n\ 00323 # from this software without specific prior written permission.\n\ 00324 #\n\ 00325 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n\ 00326 # \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n\ 00327 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n\ 00328 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n\ 00329 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n\ 00330 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n\ 00331 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n\ 00332 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n\ 00333 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n\ 00334 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n\ 00335 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n\ 00336 # POSSIBILITY OF SUCH DAMAGE.\n\ 00337 \n\ 00338 Header header\n\ 00339 #pressure sensor 24-bit value, not scaled but bias free\n\ 00340 int32 pressure\n\ 00341 \n\ 00342 #16-bit gyro readings; 32768 = 2.5V\n\ 00343 int16 gyro_x\n\ 00344 int16 gyro_y\n\ 00345 int16 gyro_z\n\ 00346 \n\ 00347 #10-bit magnetic field sensor readings\n\ 00348 int16 mag_x\n\ 00349 int16 mag_y\n\ 00350 int16 mag_z\n\ 00351 \n\ 00352 #16-bit accelerometer readings\n\ 00353 int16 acc_x\n\ 00354 int16 acc_y\n\ 00355 int16 acc_z\n\ 00356 \n\ 00357 #16-bit temperature measurement using yaw-gyro internal sensor\n\ 00358 int16 temp_gyro\n\ 00359 \n\ 00360 #16-bit temperature measurement using ADC internal sensor\n\ 00361 int32 temp_ADC\n\ 00362 \n\ 00363 ================================================================================\n\ 00364 MSG: std_msgs/Header\n\ 00365 # Standard metadata for higher-level stamped data types.\n\ 00366 # This is generally used to communicate timestamped data \n\ 00367 # in a particular coordinate frame.\n\ 00368 # \n\ 00369 # sequence ID: consecutively increasing ID \n\ 00370 uint32 seq\n\ 00371 #Two-integer timestamp that is expressed as:\n\ 00372 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00373 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00374 # time-handling sugar is provided by the client library\n\ 00375 time stamp\n\ 00376 #Frame this data is associated with\n\ 00377 # 0: no frame\n\ 00378 # 1: global frame\n\ 00379 string frame_id\n\ 00380 \n\ 00381 "; 00382 } 00383 00384 static const char* value(const ::asctec_msgs::IMURawData_<ContainerAllocator> &) { return value(); } 00385 }; 00386 00387 template<class ContainerAllocator> struct HasHeader< ::asctec_msgs::IMURawData_<ContainerAllocator> > : public TrueType {}; 00388 template<class ContainerAllocator> struct HasHeader< const ::asctec_msgs::IMURawData_<ContainerAllocator> > : public TrueType {}; 00389 } // namespace message_traits 00390 } // namespace ros 00391 00392 namespace ros 00393 { 00394 namespace serialization 00395 { 00396 00397 template<class ContainerAllocator> struct Serializer< ::asctec_msgs::IMURawData_<ContainerAllocator> > 00398 { 00399 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00400 { 00401 stream.next(m.header); 00402 stream.next(m.pressure); 00403 stream.next(m.gyro_x); 00404 stream.next(m.gyro_y); 00405 stream.next(m.gyro_z); 00406 stream.next(m.mag_x); 00407 stream.next(m.mag_y); 00408 stream.next(m.mag_z); 00409 stream.next(m.acc_x); 00410 stream.next(m.acc_y); 00411 stream.next(m.acc_z); 00412 stream.next(m.temp_gyro); 00413 stream.next(m.temp_ADC); 00414 } 00415 00416 ROS_DECLARE_ALLINONE_SERIALIZER; 00417 }; // struct IMURawData_ 00418 } // namespace serialization 00419 } // namespace ros 00420 00421 namespace ros 00422 { 00423 namespace message_operations 00424 { 00425 00426 template<class ContainerAllocator> 00427 struct Printer< ::asctec_msgs::IMURawData_<ContainerAllocator> > 00428 { 00429 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::asctec_msgs::IMURawData_<ContainerAllocator> & v) 00430 { 00431 s << indent << "header: "; 00432 s << std::endl; 00433 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header); 00434 s << indent << "pressure: "; 00435 Printer<int32_t>::stream(s, indent + " ", v.pressure); 00436 s << indent << "gyro_x: "; 00437 Printer<int16_t>::stream(s, indent + " ", v.gyro_x); 00438 s << indent << "gyro_y: "; 00439 Printer<int16_t>::stream(s, indent + " ", v.gyro_y); 00440 s << indent << "gyro_z: "; 00441 Printer<int16_t>::stream(s, indent + " ", v.gyro_z); 00442 s << indent << "mag_x: "; 00443 Printer<int16_t>::stream(s, indent + " ", v.mag_x); 00444 s << indent << "mag_y: "; 00445 Printer<int16_t>::stream(s, indent + " ", v.mag_y); 00446 s << indent << "mag_z: "; 00447 Printer<int16_t>::stream(s, indent + " ", v.mag_z); 00448 s << indent << "acc_x: "; 00449 Printer<int16_t>::stream(s, indent + " ", v.acc_x); 00450 s << indent << "acc_y: "; 00451 Printer<int16_t>::stream(s, indent + " ", v.acc_y); 00452 s << indent << "acc_z: "; 00453 Printer<int16_t>::stream(s, indent + " ", v.acc_z); 00454 s << indent << "temp_gyro: "; 00455 Printer<int16_t>::stream(s, indent + " ", v.temp_gyro); 00456 s << indent << "temp_ADC: "; 00457 Printer<int32_t>::stream(s, indent + " ", v.temp_ADC); 00458 } 00459 }; 00460 00461 00462 } // namespace message_operations 00463 } // namespace ros 00464 00465 #endif // ASCTEC_MSGS_MESSAGE_IMURAWDATA_H 00466