Class IMU
Defined in File IMU.hpp
Inheritance Relationships
Base Type
public dai::NodeCRTP< Node, IMU, IMUProperties >(Template Class NodeCRTP)
Class Documentation
-
class IMU : public dai::NodeCRTP<Node, IMU, IMUProperties>
IMU node for BNO08X.
Public Functions
Constructs IMU node.
-
void enableIMUSensor(IMUSensorConfig sensorConfig)
Enable a new IMU sensor with explicit configuration
-
void enableIMUSensor(const std::vector<IMUSensorConfig> &sensorConfigs)
Enable a list of IMU sensors with explicit configuration
-
void enableIMUSensor(IMUSensor sensor, uint32_t reportRate)
Enable a new IMU sensor with default configuration
-
void enableIMUSensor(const std::vector<IMUSensor> &sensors, uint32_t reportRate)
Enable a list of IMU sensors with default configuration
-
void setBatchReportThreshold(std::int32_t batchReportThreshold)
Above this packet threshold data will be sent to host, if queue is not blocked
-
std::int32_t getBatchReportThreshold() const
Above this packet threshold data will be sent to host, if queue is not blocked
-
void setMaxBatchReports(std::int32_t maxBatchReports)
Maximum number of IMU packets in a batch report
-
void enableFirmwareUpdate(bool enable)
Public Members
Public Static Attributes
-
static constexpr const char *NAME = "IMU"