Skip to main content

IMU

Hardware

AutomatePro features an advanced onboard 9-axis MEMS Inertial Measurement Unit (IMU). This IMU integrates a triaxial accelerometer, a triaxial gyroscope, and a magnetometer. This is output as a ROS IMU topic. The arrows on the device indicated the direction of the IMU vectors see the image below

Description of my image

IMU Specifications

ParameterValue
SensorBNO085
Sensing Types3 axis Gyroscope, 3 axis Magnetometer, 3 axis Accelerometer
Rotation Vector Error (Dynamic)13.5°
Accelerometer Accuracy10.3m/s2
Gyroscope Accuracy13.1°/s
Magnetometer Accuracy11.4uT
IMU Sensor Sample RateDefault 100Hz (configurable upto 200Hz)
Info

1 based on IC manufacture tests so results might be slightly different for AMP - see datasheet for more information

IMU

ROS API

Node: automatepro_imu_driver

Publishers

TopicTypeDescription
/sensor/imu/datasensor_msgs/msg/ImuContains orientation, angular velocity and linear acceleration.
/sensor/imu/magnetic_fieldsensor_msgs/msg/MagneticFieldContains magnetic field data.

Parameters

ParameterTypeValuesRuntime R/WDescription
frame_idstringimuread-onlyThe frame sensor data messages.
publish.imu.enabledbooltrue / falseread-onlyEnable publishing of IMU messages.
publish.imu.rateint1-200read-onlyThe data rate for the IMU in Hz.
publish.magnetic_field.enabledbooltrue / falseread-onlyMagnetometer is enabled if true.
publish.magnetic_field.rateint1-100read-onlyThe data rate for the magnetometer in Hz.

Configuration

Driver: automatepro_imu_driver
Container: automatepro-core-driver

info

All the configuration related files can be found at ~/.automatepro/config/ros directory.
These files will be mounted to docker container and will be used by the ROS driver.

config file can be found here.

~/.automatepro/config/ros/imu_params.yaml

Default Config

automatepro_imu_driver:
ros__parameters:
frame_id: "imu"
i2c:
enabled: true
bus: "/dev/i2c-7"
address: "0x4B"
publish:
magnetic_field:
enabled: true
rate: 100 # max 100 Hz
imu:
enabled: true
rate: 100 # max 200 Hz
Important

Restart the automatepro-core-driver docker container after changing the configuration.
Configurations will only be applied after the container restarts.

docker restart automatepro-core-driver

Example

Example code snippet prints the IMU data and MagneticField data by subscribing to the /sensor/imu/data and /sensor/imu/magnetic_field topics.

import rclpy
from rclpy.node import Node
from sensor_msgs.msg import Imu, MagneticField

class ImuSubscriber(Node):

def __init__(self):
super().__init__('imu_subscriber')
self.imu_subscription = self.create_subscription(
Imu,
'/sensor/imu/data',
self.imu_callback,
10)
self.magnetic_field_subscription = self.create_subscription(
MagneticField,
'/sensor/imu/magnetic_field',
self.magnetic_field_callback,
10)

def imu_callback(self, msg):
self.get_logger().info('Received IMU message: orientation=%s, angular_velocity=%s, linear_acceleration=%s' % (
msg.orientation, msg.angular_velocity, msg.linear_acceleration))

def magnetic_field_callback(self, msg):
self.get_logger().info('Received MagneticField message: magnetic_field=%s' % msg.magnetic_field)

def main(args=None):
rclpy.init(args=args)
node = ImuSubscriber()
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()

if __name__ == '__main__':
main()

Run the node using the following command:

ros2 run automatepro_py_tutorials imu_node