Class IIOWrapper
- Defined in File iio_wrapper.h 
Class Documentation
- 
class IIOWrapper
- Wrapper class for libiio library for IMU devices. - Public Functions - 
IIOWrapper()
- Constructor for IIOWrapper. 
 - 
~IIOWrapper()
- Destructor for IIOWrapper. 
 - Set the device descriptor that defines the device’s capabilities, register layout and supported features. 
 - 
int createContext(const char *context)
- create IIO context based on the given context string and search for IIO ADIS device, enable trigger and map device attributes, device channels and channels attributes. - Parameters:
- context – IIO context string 
- Returns:
- ERROR code on IIO context error, 0 otherwise 
 
 - 
bool updateBuffer(uint32_t data_selection)
- Update buffer data. This function should be called before retrieving data using getBuff** APIs. - Parameters:
- data_selection – 0 for acceleration and gyroscope data, 1 for delta angle and delta velocity data. 
- Returns:
- Return true if data was read successfully and can be retrieved, false otherwise. 
 
 - 
void stopBufferAcquisition()
- Stops buffer acquisition. 
 - 
double getBuffLinearAccelerationX()
- Get linear acceleration on x axis with buffer reads; in this case the retrieved samples are continuous if the function is called fast enough and samples are not overwritten. - Returns:
- Return the linear acceleration on x axis in m / s^2. 
 
 - 
double getBuffLinearAccelerationY()
- Get linear acceleration on y axis with buffer reads; in this case the retrieved samples are continuous if the function is called fast enough and samples are not overwritten. - Returns:
- Return the linear acceleration on y axis in m / s^2. 
 
 - 
double getBuffLinearAccelerationZ()
- Get linear acceleration on z axis with buffer reads; in this case the retrieved samples are continuous if the function is called fast enough and samples are not overwritten. - Returns:
- Return the linear acceleration on z axis in m / s^2. 
 
 - 
double getBuffAngularVelocityX()
- Get angular velocity on x axis with buffer reads; in this case the retrieved samples are continuous if the function is called fast enough and samples are not overwritten. - Returns:
- Return the angular velocity on x axis in rad / s. 
 
 - 
double getBuffAngularVelocityY()
- Get angular velocity on y axis with buffer reads; in this case the retrieved samples are continuous if the function is called fast enough and samples are not overwritten. - Returns:
- Return the angular velocity on y axis in rad / s. 
 
 - 
double getBuffAngularVelocityZ()
- Get angular velocity on z axis with buffer reads; in this case the retrieved samples are continuous if the function is called fast enough and samples are not overwritten. - Returns:
- Return the angular velocity on z axis in rad / s. 
 
 - 
double getBuffDeltaVelocityX()
- Get delta velocity on x axis with buffer reads; in this case the retrieved samples are continuous if the function is called fast enough and samples are not overwritten. - Returns:
- Return the delta velocity on x axis in m / s. 
 
 - 
double getBuffDeltaVelocityY()
- Get delta velocity on y axis with buffer reads; in this case the retrieved samples are continuous if the function is called fast enough and samples are not overwritten. - Returns:
- Return the delta velocity on y axis in m / s. 
 
 - 
double getBuffDeltaVelocityZ()
- Get delta velocity on z axis with buffer reads; in this case the retrieved samples are continuous if the function is called fast enough and samples are not overwritten. - Returns:
- Return the delta velocity on z axis in m / s. 
 
 - 
double getBuffDeltaAngleX()
- Get delta angle on x axis with buffer reads; in this case the retrieved samples are continuous if the function is called fast enough and samples are not overwritten. - Returns:
- Return the delta angle on x axis in radians. 
 
 - 
double getBuffDeltaAngleY()
- Get delta angle on y axis with buffer reads; in this case the retrieved samples are continuous if the function is called fast enough and samples are not overwritten. - Returns:
- Return the delta angle on y axis in radians. 
 
 - 
double getBuffDeltaAngleZ()
- Get delta angle on z axis with buffer reads; in this case the retrieved samples are continuous if the function is called fast enough and samples are not overwritten. - Returns:
- Return the delta angle on z axis in radians. 
 
 - 
double getBuffTemperature()
- Get temperature with buffer reads; in this case the retrieved samples are continuous if the function is called fast enough and samples are not overwritten. - Returns:
- Return the temperature in degrees Celsius. 
 
 - 
void getBuffSampleTimestamp(int32_t &sec, uint32_t &nanosec)
- Get buffer timestamp when performing buffer reads; the timestamp represent the time at which the samples from the devices were read over SPI. - Parameters:
- sec – The second component of the timestamp 
- nanosec – The nanosecond component of the timestamp 
 
 
 - 
bool getConvertedLinearAccelerationX(double &result)
- Get linear acceleration on x axis with register reads; in this case the retrieved samples are not necessary continuous. - Parameters:
- result – The linear acceleration on x axis in m / s^2. 
- Returns:
- Return true if the reading was successful and result is valid, false otherwise. 
 
 - 
bool getConvertedLinearAccelerationY(double &result)
- Get linear acceleration on y axis with register reads; in this case the retrieved samples are not necessary continuous. - Parameters:
- result – The linear acceleration on y axis in m / s^2. 
- Returns:
- Return true if the reading was successful and result is valid, false otherwise. 
 
 - 
bool getConvertedLinearAccelerationZ(double &result)
- Get linear acceleration on z axis with register reads; in this case the retrieved samples are not necessary continuous. - Parameters:
- result – The linear acceleration on z axis in m / s^2. 
- Returns:
- Return true if the reading was successful and result is valid, false otherwise. 
 
 - 
bool getConvertedAngularVelocityX(double &result)
- Get angular velocity on x axis with register reads; in this case the retrieved samples are not necessary continuous. - Parameters:
- result – The angular velocity on x axis in rad / s. 
- Returns:
- Return true if the reading was successful and result is valid, false otherwise. 
 
 - 
bool getConvertedAngularVelocityY(double &result)
- Get angular velocity on y axis with register reads; in this case the retrieved samples are not necessary continuous. - Parameters:
- result – The angular velocity on y axis in rad / s. 
- Returns:
- Return true if the reading was successful and result is valid, false otherwise. 
 
 - 
bool getConvertedAngularVelocityZ(double &result)
- Get angular velocity on z axis with register reads; in this case the retrieved samples are not necessary continuous. - Parameters:
- result – The angular velocity on z axis in rad / s. 
- Returns:
- Return true if the reading was successful and result is valid, false otherwise. 
 
 - 
bool getConvertedDeltaAngleX(double &result)
- Get delta angle on x axis with register reads; in this case the retrieved samples are not necessary continuous. - Parameters:
- result – The delta angle on x axis in radians. 
- Returns:
- Return true if the reading was successful and result is valid, false otherwise. 
 
 - 
bool getConvertedDeltaAngleY(double &result)
- Get delta angle on y axis with register reads; in this case the retrieved samples are not necessary continuous. - Parameters:
- result – The delta angle on y axis in radians. 
- Returns:
- Return true if the reading was successful and result is valid, false otherwise. 
 
 - 
bool getConvertedDeltaAngleZ(double &result)
- Get delta angle on z axis with register reads; in this case the retrieved samples are not necessary continuous. - Parameters:
- result – The delta angle on z axis in radians. 
- Returns:
- Return true if the reading was successful and result is valid, false otherwise. 
 
 - 
bool getConvertedDeltaVelocityX(double &result)
- Get delta velocity on x axis with register reads; in this case the retrieved samples are not necessary continuous. - Parameters:
- result – The delta velocity on x axis in m / s. 
- Returns:
- Return true if the reading was successful and result is valid, false otherwise. 
 
 - 
bool getConvertedDeltaVelocityY(double &result)
- Get delta velocity on y axis with register reads; in this case the retrieved samples are not necessary continuous. - Parameters:
- result – The delta velocity on y axis in m / s. 
- Returns:
- Return true if the reading was successful and result is valid, false otherwise. 
 
 - 
bool getConvertedDeltaVelocityZ(double &result)
- Get delta velocity on z axis with register reads; in this case the retrieved samples are not necessary continuous. - Parameters:
- result – The delta velocity on z axis in m / s. 
- Returns:
- Return true if the reading was successful and result is valid, false otherwise. 
 
 - 
bool getConvertedTemperature(double &result)
- Get temperature with register reads; in this case the retrieved samples are not necessary continuous. - Parameters:
- result – The temperature in degrees Celsius. 
- Returns:
- Return true if the reading was successful and result is valid, false otherwise. 
 
 - 
bool anglvel_x_calibbias(int32_t &result)
- Get angular velocity calibration offset on x axis. - Parameters:
- result – angular velocity calibration offset on x axis. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool update_anglvel_calibbias_x(int32_t val)
- Update angular velocity calibration offset on x axis. - Parameters:
- val – value to update with. 
- Returns:
- Return true if writing was with success and false if not. 
 
 - 
bool anglvel_y_calibbias(int32_t &result)
- Get angular velocity calibration offset on y axis. - Parameters:
- result – angular velocity calibration offset on y axis. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool update_anglvel_calibbias_y(int32_t val)
- Update angular velocity calibration offset on y axis. - Parameters:
- val – value to update with. 
- Returns:
- Return true if writing was with success and false if not. 
 
 - 
bool anglvel_z_calibbias(int32_t &result)
- Get angular velocity calibration offset on z axis. - Parameters:
- result – angular velocity calibration offset on z axis. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool update_anglvel_calibbias_z(int32_t val)
- Update angular velocity calibration offset on z axis. - Parameters:
- val – value to update with. 
- Returns:
- Return true if writing was with success and false if not. 
 
 - 
bool accel_x_calibbias(int32_t &result)
- Get linear acceleration calibration offset on x axis. - Parameters:
- result – linear acceleration calibration offset on x axis. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool update_accel_calibbias_x(int32_t val)
- Update linear acceleration calibration offset on x axis. - Parameters:
- val – value to update with. 
- Returns:
- Return true if writing was with success and false if not. 
 
 - 
bool accel_y_calibbias(int32_t &result)
- Get linear acceleration calibration offset on y axis. - Parameters:
- result – linear acceleration calibration offset on y axis. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool update_accel_calibbias_y(int32_t val)
- Update linear acceleration calibration offset on y axis. - Parameters:
- val – value to update with. 
- Returns:
- Return true if writing was with success and false if not. 
 
 - 
bool accel_z_calibbias(int32_t &result)
- Get linear acceleration calibration offset on z axis. - Parameters:
- result – linear acceleration calibration offset on z axis. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool update_accel_calibbias_z(int32_t val)
- Update linear acceleration calibration offset on z axis. - Parameters:
- val – value to update with. 
- Returns:
- Return true if writing was with success and false if not. 
 
 - 
bool angvel_x_filter_low_pass_3db(uint32_t &result)
- Get low pass 3db frequency data for x angular velocity. - Parameters:
- result – low pass 3db frequency value. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool update_angvel_x_filter_low_pass_3db(uint32_t val)
- Update low pass 3db frequency for x angular velocity. - Parameters:
- val – value to update with. 
- Returns:
- Return true if writing was with success and false if not. 
 
 - 
bool angvel_y_filter_low_pass_3db(uint32_t &result)
- Get low pass 3db frequency data for y angular velocity. - Parameters:
- result – low pass 3db frequency value. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool update_angvel_y_filter_low_pass_3db(uint32_t val)
- Update low pass 3db frequency for y angular velocity. - Parameters:
- val – value to update with. 
- Returns:
- Return true if writing was with success and false if not. 
 
 - 
bool angvel_z_filter_low_pass_3db(uint32_t &result)
- Get low pass 3db frequency data for z angular velocity. - Parameters:
- result – low pass 3db frequency value. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool update_angvel_z_filter_low_pass_3db(uint32_t val)
- Update low pass 3db frequency for z angular velocity. - Parameters:
- val – value to update with. 
- Returns:
- Return true if writing was with success and false if not. 
 
 - 
bool accel_x_filter_low_pass_3db(uint32_t &result)
- Get low pass 3db frequency data for x acceleration. - Parameters:
- result – low pass 3db frequency value. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool update_accel_x_filter_low_pass_3db(uint32_t val)
- Update low pass 3db frequency for x acceleration. - Parameters:
- val – value to update with. 
- Returns:
- Return true if writing was with success and false if not. 
 
 - 
bool accel_y_filter_low_pass_3db(uint32_t &result)
- Get low pass 3db frequency data for y acceleration. - Parameters:
- result – low pass 3db frequency value. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool update_accel_y_filter_low_pass_3db(uint32_t val)
- Update low pass 3db frequency for y acceleration. - Parameters:
- val – value to update with. 
- Returns:
- Return true if writing was with success and false if not. 
 
 - 
bool accel_z_filter_low_pass_3db(uint32_t &result)
- Get low pass 3db frequency data for z acceleration. - Parameters:
- result – low pass 3db frequency value. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool update_accel_z_filter_low_pass_3db(uint32_t val)
- Update low pass 3db frequency for z acceleration. - Parameters:
- val – value to update with. 
- Returns:
- Return true if writing was with success and false if not. 
 
 - 
bool filter_low_pass_3db_frequency(uint32_t &result)
- Get low pass 3db frequency data. - Parameters:
- result – low pass 3db frequency value. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool update_filter_low_pass_3db_frequency(uint32_t val)
- Update low pass 3db frequency. - Parameters:
- val – value to update with. 
- Returns:
- Return true if writing was with success and false if not. 
 
 - 
bool accel_x_calibscale(int32_t &result)
- Get linear acceleration calibration scale on x axis. - Parameters:
- result – linear acceleration calibration scale on x axis. 
- Returns:
- Return true if reading was with success and false if not. 
 
 - 
bool accel_y_calibscale(int32_t &result)
- Get linear acceleration calibration scale on y axis. - Parameters:
- result – linear acceleration calibration scale on y axis. 
- Returns:
- Return true if reading was with success and false if not. 
 
 - 
bool accel_z_calibscale(int32_t &result)
- Get linear acceleration calibration scale on z axis. - Parameters:
- result – linear acceleration calibration scale on z axis. 
- Returns:
- Return true if reading was with success and false if not. 
 
 - 
bool anglvel_x_calibscale(int32_t &result)
- Get linear angular velocity calibration scale on x axis. - Parameters:
- result – linear angular velocity calibration scale on x axis. 
- Returns:
- Return true if reading was with success and false if not. 
 
 - 
bool anglvel_y_calibscale(int32_t &result)
- Get linear angular velocity calibration scale on y axis. - Parameters:
- result – linear angular velocity calibration scale on y axis. 
- Returns:
- Return true if reading was with success and false if not. 
 
 - 
bool anglvel_z_calibscale(int32_t &result)
- Get linear angular velocity calibration scale on z axis. - Parameters:
- result – linear angular velocity calibration scale on z axis. 
- Returns:
- Return true if reading was with success and false if not. 
 
 - 
bool update_accel_calibscale_x(int32_t val)
- Update linear acceleration calibration scale on x axis. - Parameters:
- val – value to update with. 
- Returns:
- Return true if writing was with success and false if not. 
 
 - 
bool update_accel_calibscale_y(int32_t val)
- Update linear acceleration calibration scale on y axis. - Parameters:
- val – value to update with. 
- Returns:
- Return true if writing was with success and false if not. 
 
 - 
bool update_accel_calibscale_z(int32_t val)
- Update linear acceleration calibration scale on y axis. - Parameters:
- val – value to update with. 
- Returns:
- Return true if writing was with success and false if not. 
 
 - 
bool update_anglvel_calibscale_x(int32_t val)
- Update angular velocity calibration scale on x axis. - Parameters:
- val – value to update with. 
- Returns:
- Return true if writing was with success and false if not. 
 
 - 
bool update_anglvel_calibscale_y(int32_t val)
- Update angular velocity calibration scale on y axis. - Parameters:
- val – value to update with. 
- Returns:
- Return true if writing was with success and false if not. 
 
 - 
bool update_anglvel_calibscale_z(int32_t val)
- Update angular velocity calibration scale on z axis. - Parameters:
- val – value to update with. 
- Returns:
- Return true if writing was with success and false if not. 
 
 - 
bool sampling_frequency(double *result)
- Get sampling frequency. - Parameters:
- result – current set sampling frequency 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool update_sampling_frequency(double val)
- Update sampling frequency. - Parameters:
- val – value to update with. 
- Returns:
- Return true if writing was with success and false if not. 
 
 - 
bool diag_sensor_initialization_failure(bool &result)
- Get diag sensor initialization failure data. - Parameters:
- result – True if failure occurred, false otherwise. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool diag_data_path_overrun(bool &result)
- Get diag data path overrun data. - Parameters:
- result – True if failure occurred, false otherwise. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool diag_automatic_reset(bool &result)
- Get automatic reset data. - Parameters:
- result – True if device reset has occured 
- Returns:
- true Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool diag_flash_memory_update_error(bool &result)
- Get diag flash memory update_error data. - Parameters:
- result – True if failure occurred, false otherwise. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool diag_spi_communication_error(bool &result)
- Get diag spi communication error data. - Parameters:
- result – True if failure occurred, false otherwise. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool diag_crc_error(bool &result)
- Get diag crc error. - Parameters:
- result – True if calculation failure occurred in a CRC 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool diag_standby_mode(bool &result)
- Get diag standby mode data. - Parameters:
- result – True if device is in standby mode, false otherwise. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool diag_sensor_self_test_error(bool &result)
- Get diag sensor self test error data. - Parameters:
- result – True if failure occurred, false otherwise. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool diag_flash_memory_test_error(bool &result)
- Get diag flash memory test error data. - Parameters:
- result – True if failure occurred, false otherwise. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool diag_clock_error(bool &result)
- Get diag clock error data. - Parameters:
- result – True if failure occurred, false otherwise. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool diag_gyroscope1_self_test_error(bool &result)
- Get diag gyroscope1 self test error data. - Parameters:
- result – True if failure occurred, false otherwise. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool diag_gyroscope2_self_test_error(bool &result)
- Get diag gyroscope2 self test error data. - Parameters:
- result – True if failure occurred, false otherwise. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool diag_acceleration_self_test_error(bool &result)
- Get diag acceleration self test error data. - Parameters:
- result – True if failure occurred, false otherwise. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool diag_x_axis_gyroscope_failure(bool &result)
- Get diag x axis gyroscope failure data. - Parameters:
- result – True if failure occurred, false otherwise. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool diag_y_axis_gyroscope_failure(bool &result)
- Get diag y axis gyroscope failure data. - Parameters:
- result – True if failure occurred, false otherwise. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool diag_z_axis_gyroscope_failure(bool &result)
- Get diag z axis gyroscope failure data. - Parameters:
- result – True if failure occurred, false otherwise. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool diag_x_axis_accelerometer_failure(bool &result)
- Get diag x axis accelerometer failure data. - Parameters:
- result – True if failure occurred, false otherwise. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool diag_y_axis_accelerometer_failure(bool &result)
- Get diag y axis accelerometer failure data. - Parameters:
- result – True if failure occurred, false otherwise. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool diag_z_axis_accelerometer_failure(bool &result)
- Get diag z axis accelerometer failure data. - Parameters:
- result – True if failure occurred, false otherwise. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool diag_aduc_mcu_fault(bool &result)
- Get diag aduc mcu fault data. - Parameters:
- result – True if failure occurred, false otherwise. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool diag_flash_memory_write_count_exceeded_error(bool &result)
- Get diag flash memory write count exceeded error data. - Parameters:
- result – True if write count exceeded allowed value, false otherwise. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool gyroscope_measurement_range(std::string &result)
- Get gyroscope measurement range data. - Parameters:
- result – gyroscope measurement range data. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool internal_sensor_bandwidth(uint32_t &result)
- Get internal sensor bandwidth data. - Parameters:
- result – internal sensor bandwidth data. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool update_internal_sensor_bandwidth(uint32_t val)
- Update internal sensor bandwidth. - Parameters:
- val – value to update with. 
- Returns:
- Return true if writing was with success and false if not. 
 
 - 
bool point_of_percussion_alignment(uint32_t &result)
- Get point of percussion alignment data. - Parameters:
- result – point of percussion alignment data. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool update_point_of_percussion_alignment(uint32_t val)
- Update point of percussion alignment. - Parameters:
- val – value to update with. 
- Returns:
- Return true if writing was with success and false if not. 
 
 - 
bool linear_acceleration_compensation(uint32_t &result)
- Get linear acceleration compensation data. - Parameters:
- result – linear acceleration compensation data. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool update_linear_acceleration_compensation(uint32_t val)
- Update linear acceleration compensation. - Parameters:
- val – value to update with. 
- Returns:
- Return true if writing was with success and false if not. 
 
 - 
bool bias_correction_time_base_control(uint32_t &result)
- Get bias correction time base control data. - Parameters:
- result – bias correction time base control data. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool update_bias_correction_time_base_control(uint32_t val)
- Update bias correction time base control. - Parameters:
- val – value to update with. 
- Returns:
- Return true if writing was with success and false if not. 
 
 - 
bool x_axis_gyroscope_bias_correction_enable(uint32_t &result)
- Get x axis gyroscope bias correction enable data. - Parameters:
- result – x axis gyroscope bias correction enable data. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool update_x_axis_gyroscope_bias_correction_enable(uint32_t val)
- Update x axis gyroscope bias correction enable. - Parameters:
- val – value to update with. 
- Returns:
- Return true if writing was with success and false if not. 
 
 - 
bool y_axis_gyroscope_bias_correction_enable(uint32_t &result)
- Get y axis gyroscope bias correction enable data. - Parameters:
- result – y axis gyroscope bias correction enable data. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool update_y_axis_gyroscope_bias_correction_enable(uint32_t val)
- Update y axis gyroscope bias correction enable. - Parameters:
- val – value to update with. 
- Returns:
- Return true if writing was with success and false if not. 
 
 - 
bool z_axis_gyroscope_bias_correction_enable(uint32_t &result)
- Get z axis gyroscope bias correction enable data. - Parameters:
- result – z axis gyroscope bias correction enable data. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool update_z_axis_gyroscope_bias_correction_enable(uint32_t val)
- Update z axis gyroscope bias correction enable. - Parameters:
- val – value to update with. 
- Returns:
- Return true if writing was with success and false if not. 
 
 - 
bool x_axis_accelerometer_bias_correction_enable(uint32_t &result)
- Get x axis accelerometer bias correction enable data. - Parameters:
- result – x axis accelerometer bias correction enable data. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool update_x_axis_accelerometer_bias_correction_enable(uint32_t val)
- Update x axis accelerometer bias correction enable. - Parameters:
- val – value to update with. 
- Returns:
- Return true if writing was with success and false if not. 
 
 - 
bool y_axis_accelerometer_bias_correction_enable(uint32_t &result)
- Get y axis accelerometer bias correction enable data. - Parameters:
- result – y axis accelerometer bias correction enable data. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool update_y_axis_accelerometer_bias_correction_enable(uint32_t val)
- Update y axis accelerometer bias correction enable. - Parameters:
- val – value to update with. 
- Returns:
- Return true if writing was with success and false if not. 
 
 - 
bool z_axis_accelerometer_bias_correction_enable(uint32_t &result)
- Get z axis accelerometer bias correction enable data. - Parameters:
- result – z axis accelerometer bias correction enable data. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool update_z_axis_accelerometer_bias_correction_enable(uint32_t val)
- Update z axis accelerometer bias correction enable. - Parameters:
- val – value to update with. 
- Returns:
- Return true if writing was with success and false if not. 
 
 - 
bool bias_correction_update()
- Trigger a bias correction update command. - Returns:
- Return true if the command was successfully triggered, false otherwise. 
 
 - 
bool factory_calibration_restore()
- Trigger a factory calibration restore command. - Returns:
- Return true if the command was successfully triggered, false otherwise. 
 
 - 
bool sensor_self_test()
- Trigger a sensor self test command. - Returns:
- Return true if the command was successfully triggered, false otherwise. 
 
 - 
bool flash_memory_update()
- Trigger a flash memory update command. - Returns:
- Return true if the command was successfully triggered, false otherwise. 
 
 - 
bool flash_memory_test()
- Trigger a flash memory test command. - Returns:
- Return true if the command was successfully triggered, false otherwise. 
 
 - 
bool software_reset()
- Trigger a software reset command. - Returns:
- Return true if the command was successfully triggered, false otherwise. 
 
 - 
bool firmware_revision(std::string &result)
- Get firmware revision value. - Parameters:
- result – The firmware revision value. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool firmware_date(std::string &result)
- Get firmware date value. - Parameters:
- result – The firmware data value. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool product_id(uint32_t &result)
- Get product id value. - Parameters:
- result – The product id value. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool serial_number(uint32_t &result)
- Get serial number value. - Parameters:
- result – The serial number value. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
bool flash_counter(uint32_t &value)
- Get flash counter value. - Parameters:
- value – The flash counter value. 
- Returns:
- Return true if reading was successful and data is valid, false otherwise. 
 
 - 
double get_scale_accel()
- Get scale value for linear acceleration. - Returns:
- Return scale value for linear acceleration. 
 
 - 
double get_scale_anglvel()
- Get scale value for angular velocity. - Returns:
- Return scale value for angular velocity. 
 
 - 
double get_scale_deltavelocity()
- Get scale value for delta velocity. - Returns:
- Return scale value for delta velocity. 
 
 - 
double get_scale_deltaangl()
- Get scale value for delta angle. - Returns:
- Return scale value for delta angle. 
 
 - 
double get_scale_temp()
- Get scale value for temperature. - Returns:
- Return scale value for temperature. 
 
 - Public Static Functions - 
static ssize_t demux_sample(const struct iio_channel *chn, void *sample, size_t size, void *d)
 
- 
IIOWrapper()