Go to the documentation of this file.
6 #ifndef SENSOR_MSGS_MESSAGE_IMU_H
7 #define SENSOR_MSGS_MESSAGE_IMU_H
15 #include <ros/types.h>
16 #include <ros/serialization.h>
17 #include <ros/builtin_message_traits.h>
18 #include <ros/message_operations.h>
27 template <
class ContainerAllocator>
46 Imu_(
const ContainerAllocator& _alloc)
88 typedef std::shared_ptr< ::sensor_msgs::Imu_<ContainerAllocator> >
Ptr;
89 typedef std::shared_ptr< ::sensor_msgs::Imu_<ContainerAllocator>
const>
ConstPtr;
93 typedef ::sensor_msgs::Imu_<std::allocator<void> >
Imu;
95 typedef std::shared_ptr< ::sensor_msgs::Imu >
ImuPtr;
96 typedef std::shared_ptr< ::sensor_msgs::Imu const>
ImuConstPtr;
102 template<
typename ContainerAllocator>
103 std::ostream&
operator<<(std::ostream& s, const ::sensor_msgs::Imu_<ContainerAllocator> & v)
113 namespace message_traits
126 template <
class ContainerAllocator>
131 template <
class ContainerAllocator>
136 template <
class ContainerAllocator>
141 template <
class ContainerAllocator>
146 template <
class ContainerAllocator>
151 template <
class ContainerAllocator>
157 template<
class ContainerAllocator>
162 return "6a62c6daae103f4ff57a132d6f95cec2";
165 static const char*
value(const ::sensor_msgs::Imu_<ContainerAllocator>&) {
return value(); }
166 static const uint64_t static_value1 = 0x6a62c6daae103f4fULL;
167 static const uint64_t static_value2 = 0xf57a132d6f95cec2ULL;
170 template<
class ContainerAllocator>
175 return "sensor_msgs/Imu";
178 static const char*
value(const ::sensor_msgs::Imu_<ContainerAllocator>&) {
return value(); }
181 template<
class ContainerAllocator>
186 return "# This is a message to hold data from an IMU (Inertial Measurement Unit)\n\
188 # Accelerations should be in m/s^2 (not in g's), and rotational velocity should be in rad/sec\n\
190 # If the covariance of the measurement is known, it should be filled in (if all you know is the \n\
191 # variance of each measurement, e.g. from the datasheet, just put those along the diagonal)\n\
192 # A covariance matrix of all zeros will be interpreted as \"covariance unknown\", and to use the\n\
193 # data a covariance will have to be assumed or gotten from some other source\n\
195 # If you have no estimate for one of the data elements (e.g. your IMU doesn't produce an orientation \n\
196 # estimate), please set element 0 of the associated covariance matrix to -1\n\
197 # If you are interpreting this message, please check for a value of -1 in the first element of each \n\
198 # covariance matrix, and disregard the associated estimate.\n\
202 geometry_msgs/Quaternion orientation\n\
203 float64[9] orientation_covariance # Row major about x, y, z axes\n\
205 geometry_msgs/Vector3 angular_velocity\n\
206 float64[9] angular_velocity_covariance # Row major about x, y, z axes\n\
208 geometry_msgs/Vector3 linear_acceleration\n\
209 float64[9] linear_acceleration_covariance # Row major x, y z \n\
211 ================================================================================\n\
212 MSG: std_msgs/Header\n\
213 # Standard metadata for higher-level stamped data types.\n\
214 # This is generally used to communicate timestamped data \n\
215 # in a particular coordinate frame.\n\
217 # sequence ID: consecutively increasing ID \n\
219 #Two-integer timestamp that is expressed as:\n\
220 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
221 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
222 # time-handling sugar is provided by the client library\n\
224 #Frame this data is associated with\n\
229 ================================================================================\n\
230 MSG: geometry_msgs/Quaternion\n\
231 # This represents an orientation in free space in quaternion form.\n\
238 ================================================================================\n\
239 MSG: geometry_msgs/Vector3\n\
240 # This represents a vector in free space. \n\
241 # It is only meant to represent a direction. Therefore, it does not\n\
242 # make sense to apply a translation to it (e.g., when applying a \n\
243 # generic rigid transformation to a Vector3, tf2 will only apply the\n\
244 # rotation). If you want your data to be translatable too, use the\n\
245 # geometry_msgs/Point message instead.\n\
253 static const char*
value(const ::sensor_msgs::Imu_<ContainerAllocator>&) {
return value(); }
261 namespace serialization
266 template<
typename Stream,
typename T>
inline static void allInOne(
Stream& stream, T m)
268 stream.next(m.header);
269 stream.next(m.orientation);
270 stream.next(m.orientation_covariance);
271 stream.next(m.angular_velocity);
272 stream.next(m.angular_velocity_covariance);
273 stream.next(m.linear_acceleration);
274 stream.next(m.linear_acceleration_covariance);
285 namespace message_operations
288 template<
class ContainerAllocator>
291 template<
typename Stream>
static void stream(Stream& s,
const std::string&
indent, const ::sensor_msgs::Imu_<ContainerAllocator>& v)
296 s <<
indent <<
"orientation: ";
299 s <<
indent <<
"orientation_covariance[]" << std::endl;
300 for (
size_t i = 0; i < v.orientation_covariance.size(); ++i)
302 s <<
indent <<
" orientation_covariance[" << i <<
"]: ";
305 s <<
indent <<
"angular_velocity: ";
308 s <<
indent <<
"angular_velocity_covariance[]" << std::endl;
309 for (
size_t i = 0; i < v.angular_velocity_covariance.size(); ++i)
311 s <<
indent <<
" angular_velocity_covariance[" << i <<
"]: ";
314 s <<
indent <<
"linear_acceleration: ";
317 s <<
indent <<
"linear_acceleration_covariance[]" << std::endl;
318 for (
size_t i = 0; i < v.linear_acceleration_covariance.size(); ++i)
320 s <<
indent <<
" linear_acceleration_covariance[" << i <<
"]: ";
329 #endif // SENSOR_MSGS_MESSAGE_IMU_H
std::shared_ptr< ::sensor_msgs::Imu const > ImuConstPtr
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
::std_msgs::Header_< ContainerAllocator > _header_type
::sensor_msgs::Imu_< std::allocator< void > > Imu
_linear_acceleration_type linear_acceleration
Templated serialization class. Default implementation provides backwards compatibility with old messa...
_orientation_covariance_type orientation_covariance
_orientation_type orientation
std::shared_ptr< ::sensor_msgs::Imu > ImuPtr
static void stream(Stream &s, const std::string &indent, const M &value)
A fixed-size datatype is one whose size is constant, i.e. it has no variable-length arrays or strings...
#define ROS_DECLARE_ALLINONE_SERIALIZER
Declare your serializer to use an allInOne member instead of requiring 3 different serialization func...
std::shared_ptr< ::sensor_msgs::Imu_< ContainerAllocator > > Ptr
Specialize to provide the datatype for a message.
Specialize to provide the definition for a message.
Imu_< ContainerAllocator > Type
std::ostream & operator<<(std::ostream &s, const ::sensor_msgs::BatteryState_< ContainerAllocator > &v)
static void allInOne(Stream &stream, T m)
static const char * value(const ::sensor_msgs::Imu_< ContainerAllocator > &)
std::array< double, 9 > _orientation_covariance_type
static const char * value()
static const char * value()
static void stream(Stream &s, const std::string &indent, const ::sensor_msgs::Imu_< ContainerAllocator > &v)
_angular_velocity_covariance_type angular_velocity_covariance
Imu_(const ContainerAllocator &_alloc)
_linear_acceleration_covariance_type linear_acceleration_covariance
::geometry_msgs::Vector3_< ContainerAllocator > _angular_velocity_type
static const char * value(const ::sensor_msgs::Imu_< ContainerAllocator > &)
std::array< double, 9 > _angular_velocity_covariance_type
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
Specialize to provide the md5sum for a message.
static const char * value(const ::sensor_msgs::Imu_< ContainerAllocator > &)
static const char * value()
std::array< double, 9 > _linear_acceleration_covariance_type
Stream base-class, provides common functionality for IStream and OStream.
_angular_velocity_type angular_velocity
::geometry_msgs::Vector3_< ContainerAllocator > _linear_acceleration_type
std::shared_ptr< ::sensor_msgs::Imu_< ContainerAllocator > const > ConstPtr
Tools for manipulating sensor_msgs.
::geometry_msgs::Quaternion_< ContainerAllocator > _orientation_type
sick_scan_xd
Author(s): Michael Lehning
, Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:08