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