ros2_control - rolling
Public Member Functions | List of all members
semantic_components::IMUSensor Class Reference
Inheritance diagram for semantic_components::IMUSensor:
Inheritance graph
[legend]
Collaboration diagram for semantic_components::IMUSensor:
Collaboration graph
[legend]

Public Member Functions

 IMUSensor (const std::string &name)
 
std::array< double, 4 > get_orientation () const
 Return orientation. More...
 
std::array< double, 3 > get_angular_velocity () const
 Return angular velocity. More...
 
std::array< double, 3 > get_linear_acceleration () const
 Return linear acceleration. More...
 
bool get_values_as_message (sensor_msgs::msg::Imu &message) const
 Return Imu message with orientation, angular velocity and linear acceleration. More...
 
- Public Member Functions inherited from semantic_components::SemanticComponentInterface< sensor_msgs::msg::Imu >
 SemanticComponentInterface (const std::string &name, const std::vector< std::string > &interface_names)
 
 SemanticComponentInterface (const std::string &name, std::size_t size=0)
 
bool assign_loaned_state_interfaces (std::vector< hardware_interface::LoanedStateInterface > &state_interfaces)
 Assign loaned state interfaces from the hardware. More...
 
void release_interfaces ()
 Release loaned interfaces from the hardware.
 
virtual std::vector< std::string > get_state_interface_names ()
 Definition of state interface names for the component. More...
 
bool get_values (std::vector< double > &values) const
 Return all values. More...
 
bool get_values_as_message (sensor_msgs::msg::Imu &)
 Return values as MessageReturnType. More...
 

Additional Inherited Members

- Protected Attributes inherited from semantic_components::SemanticComponentInterface< sensor_msgs::msg::Imu >
std::string name_
 
std::vector< std::string > interface_names_
 
std::vector< std::reference_wrapper< hardware_interface::LoanedStateInterface > > state_interfaces_
 

Member Function Documentation

◆ get_angular_velocity()

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

Return angular velocity.

Return angular velocity reported by an IMU

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

◆ get_linear_acceleration()

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

Return linear acceleration.

Return linear acceleration reported by an IMU

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

◆ get_orientation()

std::array<double, 4> semantic_components::IMUSensor::get_orientation ( ) const
inline

Return orientation.

Return orientation reported by an IMU

Returns
Array of size 4 with orientation quaternion (x,y,z,w).

◆ get_values_as_message()

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

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;

The documentation for this class was generated from the following file: