Class IMUSensor

Inheritance Relationships

Base Type

Class Documentation

class IMUSensor : public semantic_components::SemanticComponentInterface<sensor_msgs::msg::Imu>

Public Functions

inline explicit IMUSensor(const std::string &name)
virtual ~IMUSensor() = default
inline std::array<double, 4> get_orientation()

Return orientation.

Return orientation reported by an IMU

Returns:

array of size 4 with orientation quaternion (x,y,z,w)

inline std::array<double, 3> get_angular_velocity()

Return angular velocity.

Return angular velocity reported by an IMU

Returns:

array of size 3 with angular velocity values.

inline std::array<double, 3> get_linear_acceleration()

Return linear acceleration.

Return linear acceleration reported by an IMU

Returns:

array of size 3 with linear acceleration values.

inline bool get_values_as_message(sensor_msgs::msg::Imu &message)

Return Imu message with orientation, angular velocity and linear acceleration.

Constructs and return a IMU message from the current values.

Returns:

imu message from values;

Protected Attributes

std::array<double, 4> orientation_
std::array<double, 3> angular_velocity_
std::array<double, 3> linear_acceleration_