IMU Sensor Broadcaster

Broadcaster of messages from IMU sensor. The published message type is sensor_msgs/msg/Imu.

The controller is a wrapper around IMUSensor semantic component (see controller_interface package).

Parameters

This controller uses the generate_parameter_library to handle its parameters. The parameter definition file located in the src folder contains descriptions for all the parameters used by the controller.

List of parameters

sensor_name (string)

Defines sensor name used as prefix for its interfaces. Interface names are: <sensor_name>/orientation.x, ..., <sensor_name>/angular_velocity.x, ..., <sensor_name>/linear_acceleration.x.

Read only: True

Default: “”

Constraints:

  • parameter is not empty

frame_id (string)

Sensor’s frame_id in which values are published.

Read only: True

Default: “”

Constraints:

  • parameter is not empty

static_covariance_orientation (double_array)

Static orientation covariance. Row major about x, y, z axes

Read only: True

Default: {0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0}

Constraints:

  • length must be equal to 9

static_covariance_angular_velocity (double_array)

Static angular velocity covariance. Row major about x, y, z axes

Read only: True

Default: {0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0}

Constraints:

  • length must be equal to 9

static_covariance_linear_acceleration (double_array)

Static linear acceleration covariance. Row major about x, y, z axes

Read only: True

Default: {0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0}

Constraints:

  • length must be equal to 9

rotation_offset.roll (double)

Roll offset value in radians. (Z-Y’-X’’ convention)

Read only: True

Default: 0.0

rotation_offset.pitch (double)

Pitch offset value in radians. (Z-Y’-X’’ convention)

Read only: True

Default: 0.0

rotation_offset.yaw (double)

Yaw offset value in radians. (Z-Y’-X’’ convention)

Read only: True

Default: 0.0

An example parameter file

An example parameter file for this controller can be found in the test directory:

test_imu_sensor_broadcaster:
  ros__parameters:

    sensor_name: "imu_sensor"
    frame_id:  "imu_sensor_frame"