|
| IMUSensor (const std::string &name) |
|
std::array< double, 4 > | get_orientation () const |
| Return orientation.
|
|
std::array< double, 3 > | get_angular_velocity () const |
| Return angular velocity.
|
|
std::array< double, 3 > | get_linear_acceleration () const |
| Return linear acceleration.
|
|
bool | get_values_as_message (sensor_msgs::msg::Imu &message) const |
| Return Imu message with orientation, angular velocity and linear acceleration.
|
|
| 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.
|
|
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.
|
|
bool | get_values (std::vector< double > &values) const |
| Return all values.
|
|
bool | get_values_as_message (sensor_msgs::msg::Imu &) |
| Return values as MessageReturnType.
|
|
◆ 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:
- ros2_control/controller_interface/include/semantic_components/imu_sensor.hpp