Class ImuConverter

Class Documentation

class ImuConverter

Public Functions

ImuConverter(const std::string &frameName, ImuSyncMethod syncMode = ImuSyncMethod::LINEAR_INTERPOLATE_ACCEL, double linear_accel_cov = 0.0, double angular_velocity_cov = 0.0, double rotation_cov = 0.0, double magnetic_field_cov = 0.0, bool enable_rotation = false, bool enable_magn = false, bool getBaseDeviceTimestamp = false)
~ImuConverter()
void updateRosBaseTime()

Handles cases in which the ROS time shifts forward or backward Should be called at regular intervals or on-change of ROS time, depending on monitoring.

inline void setUpdateRosBaseTimeOnToRosMsg(bool update = true)

Commands the converter to automatically update the ROS base time on message conversion based on variable.

Parameters:

update – bool whether to automatically update the ROS base time on message conversion

void toRosMsg(std::shared_ptr<dai::IMUData> inData, std::deque<ImuMsgs::Imu> &outImuMsgs)
void toRosDaiMsg(std::shared_ptr<dai::IMUData> inData, std::deque<depthai_ros_msgs::msg::ImuWithMagneticField> &outImuMsgs)
template<typename T>
inline T lerp(const T &a, const T &b, const double t)
template<typename T>
inline T lerpImu(const T &a, const T &b, const double t)