$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/sensor_msgs/msg/Imu.msg */ 00002 #ifndef SENSOR_MSGS_MESSAGE_IMU_H 00003 #define SENSOR_MSGS_MESSAGE_IMU_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/Quaternion.h" 00019 #include "geometry_msgs/Vector3.h" 00020 #include "geometry_msgs/Vector3.h" 00021 00022 namespace sensor_msgs 00023 { 00024 template <class ContainerAllocator> 00025 struct Imu_ { 00026 typedef Imu_<ContainerAllocator> Type; 00027 00028 Imu_() 00029 : header() 00030 , orientation() 00031 , orientation_covariance() 00032 , angular_velocity() 00033 , angular_velocity_covariance() 00034 , linear_acceleration() 00035 , linear_acceleration_covariance() 00036 { 00037 orientation_covariance.assign(0.0); 00038 angular_velocity_covariance.assign(0.0); 00039 linear_acceleration_covariance.assign(0.0); 00040 } 00041 00042 Imu_(const ContainerAllocator& _alloc) 00043 : header(_alloc) 00044 , orientation(_alloc) 00045 , orientation_covariance() 00046 , angular_velocity(_alloc) 00047 , angular_velocity_covariance() 00048 , linear_acceleration(_alloc) 00049 , linear_acceleration_covariance() 00050 { 00051 orientation_covariance.assign(0.0); 00052 angular_velocity_covariance.assign(0.0); 00053 linear_acceleration_covariance.assign(0.0); 00054 } 00055 00056 typedef ::std_msgs::Header_<ContainerAllocator> _header_type; 00057 ::std_msgs::Header_<ContainerAllocator> header; 00058 00059 typedef ::geometry_msgs::Quaternion_<ContainerAllocator> _orientation_type; 00060 ::geometry_msgs::Quaternion_<ContainerAllocator> orientation; 00061 00062 typedef boost::array<double, 9> _orientation_covariance_type; 00063 boost::array<double, 9> orientation_covariance; 00064 00065 typedef ::geometry_msgs::Vector3_<ContainerAllocator> _angular_velocity_type; 00066 ::geometry_msgs::Vector3_<ContainerAllocator> angular_velocity; 00067 00068 typedef boost::array<double, 9> _angular_velocity_covariance_type; 00069 boost::array<double, 9> angular_velocity_covariance; 00070 00071 typedef ::geometry_msgs::Vector3_<ContainerAllocator> _linear_acceleration_type; 00072 ::geometry_msgs::Vector3_<ContainerAllocator> linear_acceleration; 00073 00074 typedef boost::array<double, 9> _linear_acceleration_covariance_type; 00075 boost::array<double, 9> linear_acceleration_covariance; 00076 00077 00078 ROS_DEPRECATED uint32_t get_orientation_covariance_size() const { return (uint32_t)orientation_covariance.size(); } 00079 ROS_DEPRECATED uint32_t get_angular_velocity_covariance_size() const { return (uint32_t)angular_velocity_covariance.size(); } 00080 ROS_DEPRECATED uint32_t get_linear_acceleration_covariance_size() const { return (uint32_t)linear_acceleration_covariance.size(); } 00081 private: 00082 static const char* __s_getDataType_() { return "sensor_msgs/Imu"; } 00083 public: 00084 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00085 00086 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00087 00088 private: 00089 static const char* __s_getMD5Sum_() { return "6a62c6daae103f4ff57a132d6f95cec2"; } 00090 public: 00091 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00092 00093 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00094 00095 private: 00096 static const char* __s_getMessageDefinition_() { return "# This is a message to hold data from an IMU (Inertial Measurement Unit)\n\ 00097 #\n\ 00098 # Accelerations should be in m/s^2 (not in g's), and rotational velocity should be in rad/sec\n\ 00099 #\n\ 00100 # If the covariance of the measurement is known, it should be filled in (if all you know is the variance of each measurement, e.g. from the datasheet, just put those along the diagonal)\n\ 00101 # A covariance matrix of all zeros will be interpreted as \"covariance unknown\", and to use the data a covariance will have to be assumed or gotten from some other source\n\ 00102 #\n\ 00103 # If you have no estimate for one of the data elements (e.g. your IMU doesn't produce an orientation estimate), please set element 0 of the associated covariance matrix to -1\n\ 00104 # If you are interpreting this message, please check for a value of -1 in the first element of each covariance matrix, and disregard the associated estimate.\n\ 00105 \n\ 00106 Header header\n\ 00107 \n\ 00108 geometry_msgs/Quaternion orientation\n\ 00109 float64[9] orientation_covariance # Row major about x, y, z axes\n\ 00110 \n\ 00111 geometry_msgs/Vector3 angular_velocity\n\ 00112 float64[9] angular_velocity_covariance # Row major about x, y, z axes\n\ 00113 \n\ 00114 geometry_msgs/Vector3 linear_acceleration\n\ 00115 float64[9] linear_acceleration_covariance # Row major x, y z \n\ 00116 \n\ 00117 ================================================================================\n\ 00118 MSG: std_msgs/Header\n\ 00119 # Standard metadata for higher-level stamped data types.\n\ 00120 # This is generally used to communicate timestamped data \n\ 00121 # in a particular coordinate frame.\n\ 00122 # \n\ 00123 # sequence ID: consecutively increasing ID \n\ 00124 uint32 seq\n\ 00125 #Two-integer timestamp that is expressed as:\n\ 00126 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00127 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00128 # time-handling sugar is provided by the client library\n\ 00129 time stamp\n\ 00130 #Frame this data is associated with\n\ 00131 # 0: no frame\n\ 00132 # 1: global frame\n\ 00133 string frame_id\n\ 00134 \n\ 00135 ================================================================================\n\ 00136 MSG: geometry_msgs/Quaternion\n\ 00137 # This represents an orientation in free space in quaternion form.\n\ 00138 \n\ 00139 float64 x\n\ 00140 float64 y\n\ 00141 float64 z\n\ 00142 float64 w\n\ 00143 \n\ 00144 ================================================================================\n\ 00145 MSG: geometry_msgs/Vector3\n\ 00146 # This represents a vector in free space. \n\ 00147 \n\ 00148 float64 x\n\ 00149 float64 y\n\ 00150 float64 z\n\ 00151 "; } 00152 public: 00153 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00154 00155 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00156 00157 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00158 { 00159 ros::serialization::OStream stream(write_ptr, 1000000000); 00160 ros::serialization::serialize(stream, header); 00161 ros::serialization::serialize(stream, orientation); 00162 ros::serialization::serialize(stream, orientation_covariance); 00163 ros::serialization::serialize(stream, angular_velocity); 00164 ros::serialization::serialize(stream, angular_velocity_covariance); 00165 ros::serialization::serialize(stream, linear_acceleration); 00166 ros::serialization::serialize(stream, linear_acceleration_covariance); 00167 return stream.getData(); 00168 } 00169 00170 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00171 { 00172 ros::serialization::IStream stream(read_ptr, 1000000000); 00173 ros::serialization::deserialize(stream, header); 00174 ros::serialization::deserialize(stream, orientation); 00175 ros::serialization::deserialize(stream, orientation_covariance); 00176 ros::serialization::deserialize(stream, angular_velocity); 00177 ros::serialization::deserialize(stream, angular_velocity_covariance); 00178 ros::serialization::deserialize(stream, linear_acceleration); 00179 ros::serialization::deserialize(stream, linear_acceleration_covariance); 00180 return stream.getData(); 00181 } 00182 00183 ROS_DEPRECATED virtual uint32_t serializationLength() const 00184 { 00185 uint32_t size = 0; 00186 size += ros::serialization::serializationLength(header); 00187 size += ros::serialization::serializationLength(orientation); 00188 size += ros::serialization::serializationLength(orientation_covariance); 00189 size += ros::serialization::serializationLength(angular_velocity); 00190 size += ros::serialization::serializationLength(angular_velocity_covariance); 00191 size += ros::serialization::serializationLength(linear_acceleration); 00192 size += ros::serialization::serializationLength(linear_acceleration_covariance); 00193 return size; 00194 } 00195 00196 typedef boost::shared_ptr< ::sensor_msgs::Imu_<ContainerAllocator> > Ptr; 00197 typedef boost::shared_ptr< ::sensor_msgs::Imu_<ContainerAllocator> const> ConstPtr; 00198 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00199 }; // struct Imu 00200 typedef ::sensor_msgs::Imu_<std::allocator<void> > Imu; 00201 00202 typedef boost::shared_ptr< ::sensor_msgs::Imu> ImuPtr; 00203 typedef boost::shared_ptr< ::sensor_msgs::Imu const> ImuConstPtr; 00204 00205 00206 template<typename ContainerAllocator> 00207 std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::Imu_<ContainerAllocator> & v) 00208 { 00209 ros::message_operations::Printer< ::sensor_msgs::Imu_<ContainerAllocator> >::stream(s, "", v); 00210 return s;} 00211 00212 } // namespace sensor_msgs 00213 00214 namespace ros 00215 { 00216 namespace message_traits 00217 { 00218 template<class ContainerAllocator> struct IsMessage< ::sensor_msgs::Imu_<ContainerAllocator> > : public TrueType {}; 00219 template<class ContainerAllocator> struct IsMessage< ::sensor_msgs::Imu_<ContainerAllocator> const> : public TrueType {}; 00220 template<class ContainerAllocator> 00221 struct MD5Sum< ::sensor_msgs::Imu_<ContainerAllocator> > { 00222 static const char* value() 00223 { 00224 return "6a62c6daae103f4ff57a132d6f95cec2"; 00225 } 00226 00227 static const char* value(const ::sensor_msgs::Imu_<ContainerAllocator> &) { return value(); } 00228 static const uint64_t static_value1 = 0x6a62c6daae103f4fULL; 00229 static const uint64_t static_value2 = 0xf57a132d6f95cec2ULL; 00230 }; 00231 00232 template<class ContainerAllocator> 00233 struct DataType< ::sensor_msgs::Imu_<ContainerAllocator> > { 00234 static const char* value() 00235 { 00236 return "sensor_msgs/Imu"; 00237 } 00238 00239 static const char* value(const ::sensor_msgs::Imu_<ContainerAllocator> &) { return value(); } 00240 }; 00241 00242 template<class ContainerAllocator> 00243 struct Definition< ::sensor_msgs::Imu_<ContainerAllocator> > { 00244 static const char* value() 00245 { 00246 return "# This is a message to hold data from an IMU (Inertial Measurement Unit)\n\ 00247 #\n\ 00248 # Accelerations should be in m/s^2 (not in g's), and rotational velocity should be in rad/sec\n\ 00249 #\n\ 00250 # If the covariance of the measurement is known, it should be filled in (if all you know is the variance of each measurement, e.g. from the datasheet, just put those along the diagonal)\n\ 00251 # A covariance matrix of all zeros will be interpreted as \"covariance unknown\", and to use the data a covariance will have to be assumed or gotten from some other source\n\ 00252 #\n\ 00253 # If you have no estimate for one of the data elements (e.g. your IMU doesn't produce an orientation estimate), please set element 0 of the associated covariance matrix to -1\n\ 00254 # If you are interpreting this message, please check for a value of -1 in the first element of each covariance matrix, and disregard the associated estimate.\n\ 00255 \n\ 00256 Header header\n\ 00257 \n\ 00258 geometry_msgs/Quaternion orientation\n\ 00259 float64[9] orientation_covariance # Row major about x, y, z axes\n\ 00260 \n\ 00261 geometry_msgs/Vector3 angular_velocity\n\ 00262 float64[9] angular_velocity_covariance # Row major about x, y, z axes\n\ 00263 \n\ 00264 geometry_msgs/Vector3 linear_acceleration\n\ 00265 float64[9] linear_acceleration_covariance # Row major x, y z \n\ 00266 \n\ 00267 ================================================================================\n\ 00268 MSG: std_msgs/Header\n\ 00269 # Standard metadata for higher-level stamped data types.\n\ 00270 # This is generally used to communicate timestamped data \n\ 00271 # in a particular coordinate frame.\n\ 00272 # \n\ 00273 # sequence ID: consecutively increasing ID \n\ 00274 uint32 seq\n\ 00275 #Two-integer timestamp that is expressed as:\n\ 00276 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00277 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00278 # time-handling sugar is provided by the client library\n\ 00279 time stamp\n\ 00280 #Frame this data is associated with\n\ 00281 # 0: no frame\n\ 00282 # 1: global frame\n\ 00283 string frame_id\n\ 00284 \n\ 00285 ================================================================================\n\ 00286 MSG: geometry_msgs/Quaternion\n\ 00287 # This represents an orientation in free space in quaternion form.\n\ 00288 \n\ 00289 float64 x\n\ 00290 float64 y\n\ 00291 float64 z\n\ 00292 float64 w\n\ 00293 \n\ 00294 ================================================================================\n\ 00295 MSG: geometry_msgs/Vector3\n\ 00296 # This represents a vector in free space. \n\ 00297 \n\ 00298 float64 x\n\ 00299 float64 y\n\ 00300 float64 z\n\ 00301 "; 00302 } 00303 00304 static const char* value(const ::sensor_msgs::Imu_<ContainerAllocator> &) { return value(); } 00305 }; 00306 00307 template<class ContainerAllocator> struct HasHeader< ::sensor_msgs::Imu_<ContainerAllocator> > : public TrueType {}; 00308 template<class ContainerAllocator> struct HasHeader< const ::sensor_msgs::Imu_<ContainerAllocator> > : public TrueType {}; 00309 } // namespace message_traits 00310 } // namespace ros 00311 00312 namespace ros 00313 { 00314 namespace serialization 00315 { 00316 00317 template<class ContainerAllocator> struct Serializer< ::sensor_msgs::Imu_<ContainerAllocator> > 00318 { 00319 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00320 { 00321 stream.next(m.header); 00322 stream.next(m.orientation); 00323 stream.next(m.orientation_covariance); 00324 stream.next(m.angular_velocity); 00325 stream.next(m.angular_velocity_covariance); 00326 stream.next(m.linear_acceleration); 00327 stream.next(m.linear_acceleration_covariance); 00328 } 00329 00330 ROS_DECLARE_ALLINONE_SERIALIZER; 00331 }; // struct Imu_ 00332 } // namespace serialization 00333 } // namespace ros 00334 00335 namespace ros 00336 { 00337 namespace message_operations 00338 { 00339 00340 template<class ContainerAllocator> 00341 struct Printer< ::sensor_msgs::Imu_<ContainerAllocator> > 00342 { 00343 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::Imu_<ContainerAllocator> & v) 00344 { 00345 s << indent << "header: "; 00346 s << std::endl; 00347 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header); 00348 s << indent << "orientation: "; 00349 s << std::endl; 00350 Printer< ::geometry_msgs::Quaternion_<ContainerAllocator> >::stream(s, indent + " ", v.orientation); 00351 s << indent << "orientation_covariance[]" << std::endl; 00352 for (size_t i = 0; i < v.orientation_covariance.size(); ++i) 00353 { 00354 s << indent << " orientation_covariance[" << i << "]: "; 00355 Printer<double>::stream(s, indent + " ", v.orientation_covariance[i]); 00356 } 00357 s << indent << "angular_velocity: "; 00358 s << std::endl; 00359 Printer< ::geometry_msgs::Vector3_<ContainerAllocator> >::stream(s, indent + " ", v.angular_velocity); 00360 s << indent << "angular_velocity_covariance[]" << std::endl; 00361 for (size_t i = 0; i < v.angular_velocity_covariance.size(); ++i) 00362 { 00363 s << indent << " angular_velocity_covariance[" << i << "]: "; 00364 Printer<double>::stream(s, indent + " ", v.angular_velocity_covariance[i]); 00365 } 00366 s << indent << "linear_acceleration: "; 00367 s << std::endl; 00368 Printer< ::geometry_msgs::Vector3_<ContainerAllocator> >::stream(s, indent + " ", v.linear_acceleration); 00369 s << indent << "linear_acceleration_covariance[]" << std::endl; 00370 for (size_t i = 0; i < v.linear_acceleration_covariance.size(); ++i) 00371 { 00372 s << indent << " linear_acceleration_covariance[" << i << "]: "; 00373 Printer<double>::stream(s, indent + " ", v.linear_acceleration_covariance[i]); 00374 } 00375 } 00376 }; 00377 00378 00379 } // namespace message_operations 00380 } // namespace ros 00381 00382 #endif // SENSOR_MSGS_MESSAGE_IMU_H 00383