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)
inline std::array<double, 4> get_orientation() const

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() const

Return angular velocity.

Return angular velocity reported by an IMU

Returns:

array of size 3 with angular velocity values (x, y, z).

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

Return linear acceleration.

Return linear acceleration reported by an IMU

Returns:

array of size 3 with linear acceleration values (x, y, z).

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

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;