5 #ifndef SENSOR_MSGS_MESSAGE_IMU_H 6 #define SENSOR_MSGS_MESSAGE_IMU_H 26 template <
class ContainerAllocator>
45 Imu_(
const ContainerAllocator& _alloc)
87 typedef std::shared_ptr< ::sensor_msgs::Imu_<ContainerAllocator> >
Ptr;
88 typedef std::shared_ptr< ::sensor_msgs::Imu_<ContainerAllocator>
const>
ConstPtr;
92 typedef ::sensor_msgs::Imu_<std::allocator<void> >
Imu;
94 typedef std::shared_ptr< ::sensor_msgs::Imu >
ImuPtr;
95 typedef std::shared_ptr< ::sensor_msgs::Imu const>
ImuConstPtr;
101 template<
typename ContainerAllocator>
102 std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::Imu_<ContainerAllocator> &
v)
112 namespace message_traits
125 template <
class ContainerAllocator>
130 template <
class ContainerAllocator>
135 template <
class ContainerAllocator>
140 template <
class ContainerAllocator>
145 template <
class ContainerAllocator>
150 template <
class ContainerAllocator>
156 template<
class ContainerAllocator>
161 return "6a62c6daae103f4ff57a132d6f95cec2";
164 static const char*
value(const ::sensor_msgs::Imu_<ContainerAllocator>&) {
return value(); }
165 static const uint64_t static_value1 = 0x6a62c6daae103f4fULL;
166 static const uint64_t static_value2 = 0xf57a132d6f95cec2ULL;
169 template<
class ContainerAllocator>
174 return "sensor_msgs/Imu";
177 static const char*
value(const ::sensor_msgs::Imu_<ContainerAllocator>&) {
return value(); }
180 template<
class ContainerAllocator>
185 return "# This is a message to hold data from an IMU (Inertial Measurement Unit)\n\ 187 # Accelerations should be in m/s^2 (not in g's), and rotational velocity should be in rad/sec\n\ 189 # If the covariance of the measurement is known, it should be filled in (if all you know is the \n\ 190 # variance of each measurement, e.g. from the datasheet, just put those along the diagonal)\n\ 191 # A covariance matrix of all zeros will be interpreted as \"covariance unknown\", and to use the\n\ 192 # data a covariance will have to be assumed or gotten from some other source\n\ 194 # If you have no estimate for one of the data elements (e.g. your IMU doesn't produce an orientation \n\ 195 # estimate), please set element 0 of the associated covariance matrix to -1\n\ 196 # If you are interpreting this message, please check for a value of -1 in the first element of each \n\ 197 # covariance matrix, and disregard the associated estimate.\n\ 201 geometry_msgs/Quaternion orientation\n\ 202 float64[9] orientation_covariance # Row major about x, y, z axes\n\ 204 geometry_msgs/Vector3 angular_velocity\n\ 205 float64[9] angular_velocity_covariance # Row major about x, y, z axes\n\ 207 geometry_msgs/Vector3 linear_acceleration\n\ 208 float64[9] linear_acceleration_covariance # Row major x, y z \n\ 210 ================================================================================\n\ 211 MSG: std_msgs/Header\n\ 212 # Standard metadata for higher-level stamped data types.\n\ 213 # This is generally used to communicate timestamped data \n\ 214 # in a particular coordinate frame.\n\ 216 # sequence ID: consecutively increasing ID \n\ 218 #Two-integer timestamp that is expressed as:\n\ 219 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ 220 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ 221 # time-handling sugar is provided by the client library\n\ 223 #Frame this data is associated with\n\ 228 ================================================================================\n\ 229 MSG: geometry_msgs/Quaternion\n\ 230 # This represents an orientation in free space in quaternion form.\n\ 237 ================================================================================\n\ 238 MSG: geometry_msgs/Vector3\n\ 239 # This represents a vector in free space. \n\ 240 # It is only meant to represent a direction. Therefore, it does not\n\ 241 # make sense to apply a translation to it (e.g., when applying a \n\ 242 # generic rigid transformation to a Vector3, tf2 will only apply the\n\ 243 # rotation). If you want your data to be translatable too, use the\n\ 244 # geometry_msgs/Point message instead.\n\ 252 static const char*
value(const ::sensor_msgs::Imu_<ContainerAllocator>&) {
return value(); }
260 namespace serialization
267 stream.next(m.header);
268 stream.next(m.orientation);
269 stream.next(m.orientation_covariance);
270 stream.next(m.angular_velocity);
271 stream.next(m.angular_velocity_covariance);
272 stream.next(m.linear_acceleration);
273 stream.next(m.linear_acceleration_covariance);
284 namespace message_operations
287 template<
class ContainerAllocator>
290 template<
typename Stream>
static void stream(Stream&
s,
const std::string& indent, const ::sensor_msgs::Imu_<ContainerAllocator>&
v)
292 s << indent <<
"header: ";
295 s << indent <<
"orientation: ";
298 s << indent <<
"orientation_covariance[]" << std::endl;
299 for (
size_t i = 0;
i < v.orientation_covariance.size(); ++
i)
301 s << indent <<
" orientation_covariance[" <<
i <<
"]: ";
304 s << indent <<
"angular_velocity: ";
307 s << indent <<
"angular_velocity_covariance[]" << std::endl;
308 for (
size_t i = 0;
i < v.angular_velocity_covariance.size(); ++
i)
310 s << indent <<
" angular_velocity_covariance[" <<
i <<
"]: ";
313 s << indent <<
"linear_acceleration: ";
316 s << indent <<
"linear_acceleration_covariance[]" << std::endl;
317 for (
size_t i = 0;
i < v.linear_acceleration_covariance.size(); ++
i)
319 s << indent <<
" linear_acceleration_covariance[" <<
i <<
"]: ";
328 #endif // SENSOR_MSGS_MESSAGE_IMU_H std::shared_ptr< ::sensor_msgs::Imu_< ContainerAllocator > const > ConstPtr
std::shared_ptr< ::sensor_msgs::Imu const > ImuConstPtr
typedef void(APIENTRY *GLDEBUGPROC)(GLenum source
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
_linear_acceleration_type linear_acceleration
Specialize to provide the md5sum for a message.
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
_angular_velocity_covariance_type angular_velocity_covariance
static const char * value()
std::shared_ptr< ::sensor_msgs::Imu > ImuPtr
GLsizei const GLchar *const * string
_orientation_type orientation
Specialize to provide the datatype for a message.
static const char * value(const ::sensor_msgs::Imu_< ContainerAllocator > &)
A fixed-size datatype is one whose size is constant, i.e. it has no variable-length arrays or strings...
Stream base-class, provides common functionality for IStream and OStream.
::std_msgs::Header_< ContainerAllocator > _header_type
::geometry_msgs::Vector3_< ContainerAllocator > _angular_velocity_type
static const char * value()
static void allInOne(Stream &stream, T m)
Tools for manipulating sensor_msgs.
std::array< double, 9 > _angular_velocity_covariance_type
Imu_(const ContainerAllocator &_alloc)
#define ROS_DECLARE_ALLINONE_SERIALIZER
Declare your serializer to use an allInOne member instead of requiring 3 different serialization func...
unsigned __int64 uint64_t
Specialize to provide the definition for a message.
::geometry_msgs::Quaternion_< ContainerAllocator > _orientation_type
static const char * value(const ::sensor_msgs::Imu_< ContainerAllocator > &)
static void stream(Stream &s, const std::string &indent, const ::sensor_msgs::Imu_< ContainerAllocator > &v)
Imu_< ContainerAllocator > Type
_angular_velocity_type angular_velocity
std::array< double, 9 > _orientation_covariance_type
static const char * value()
_orientation_covariance_type orientation_covariance
_linear_acceleration_covariance_type linear_acceleration_covariance
::geometry_msgs::Vector3_< ContainerAllocator > _linear_acceleration_type
Templated serialization class. Default implementation provides backwards compatibility with old messa...
::sensor_msgs::Imu_< std::allocator< void > > Imu
static const char * value(const ::sensor_msgs::Imu_< ContainerAllocator > &)
std::array< double, 9 > _linear_acceleration_covariance_type
std::shared_ptr< ::sensor_msgs::Imu_< ContainerAllocator > > Ptr