Classes | Enumerations | Functions
rsimpl::motion_module Namespace Reference

Classes

struct  fw_image_packet
struct  mm_config
struct  motion_event
struct  motion_event_status
class  motion_module_control
struct  motion_module_parser
class  motion_module_state
struct  motion_module_wraparound

Enumerations

enum  adaptor_board_command {
  IRB = 0x01, IWB = 0x02, GVD = 0x03, IAP_IRB = 0x04,
  IAP_IWB = 0x05, FRCNT = 0x06, GLD = 0x07, GPW = 0x08,
  GPR = 0x09, MMPWR = 0x0A, DSPWR = 0x0B, EXT_TRIG = 0x0C,
  CX3FWUPD = 0x0D, MM_SNB = 0x10, MM_TRB = 0x11, MM_ACTIVATE = 0x0E
}
enum  i2c_register {
  REG_UCTRL_CFG = 0x00, REG_INT_ID_CONFIG = 0x04, REG_INT_TYPE_CONFIG = 0x08, REG_EEPROM_CMD = 0x0C,
  REG_EEPROM_DATA = 0xD0, REG_TIMER_PRESCALER = 0x14, REG_TIMER_RESET_VALUE = 0x18, REG_GYRO_BYPASS_CMD1 = 0x1C,
  REG_GYRO_BYPASS_CMD2 = 0x20, REG_GYRO_BYPASS_RDOUT1 = 0x24, REG_GYRO_BYPASS_RDOUT2 = 0x28, REG_ACC_BYPASS_CMD1 = 0x2C,
  REG_ACC_BYPASS_CMD2 = 0x30, REG_ACC_BYPASS_RDOUT1 = 0x34, REG_ACC_BYPASS_RDOUT2 = 0x38, REG_REQ_LTR = 0x3C,
  REG_STATUS_REG = 0x40, REG_FIFO_RD = 0x44, REG_FIRST_INT_IGNORE = 0x48, REG_IAP_REG = 0x4C,
  REG_INT_ENABLE = 0x50, REG_CURR_PWR_STATE = 0x54, REG_NEXT_PWR_STATE = 0x58, REG_ACC_BW = 0x5C,
  REG_GYRO_BW = 0x60, REG_ACC_RANGE = 0x64, REG_GYRO_RANGE = 0x68, REG_IMG_VER = 0x6C,
  REG_ERROR = 0x70, REG_JUMP_TO_APP = 0x77
}
enum  mm_accel_bandwidth { accel_bw_default = 0, accel_bw_125hz = 1, accel_bw_250hz = 2 }
enum  mm_accel_range { accel_range_default = 0, accel_range_4g = 1, accel_range_8g = 2, accel_range_16g = 3 }
enum  mm_gyro_bandwidth { gyro_bw_default = 0, gyro_bw_200hz = 1 }
enum  mm_gyro_range { gyro_range_default = 0, gyro_range_1000 = 1, gyro_range_2000 = 2 }
enum  mm_request { mm_output_undefined = 0, mm_video_output = 1, mm_events_output = 2 }
enum  mm_state { mm_idle = 0, mm_streaming = 1, mm_eventing = 2, mm_full_load = 3 }
enum  motion_module_errors {
  imu_not_responding = 0, illegal_configuration = 1, ts_fifo_overflow = 2, imu_fifo_overflow = 3,
  watchdog_reset = 4, crc_error = 5, missing_data_from_imu = 6, bootloader_failure = 7,
  eeprom_error = 8, bist_check_failed = 9, uctrl_not_responding = 10, cx3_fifo_overflow = 11,
  general_cx3_failure = 12, cx3_usb_failure = 13, reserved_1 = 14, reserved_2 = 15,
  max_mm_error
}
enum  power_states {
  PWR_STATE_DNR = 0x00, PWR_STATE_INIT = 0x02, PWR_STATE_ACTIVE = 0x03, PWR_STATE_PAUSE = 0x04,
  PWR_STATE_IAP = 0x05
}

Functions

void config (uvc::device &device, uint8_t gyro_bw, uint8_t gyro_range, uint8_t accel_bw, uint8_t accel_range, uint32_t time_seed)
const char * get_mm_request_name (mm_request request)
const char * get_mm_state_name (mm_state state)

Enumeration Type Documentation

Enumerator:
IRB 
IWB 
GVD 
IAP_IRB 
IAP_IWB 
FRCNT 
GLD 
GPW 
GPR 
MMPWR 
DSPWR 
EXT_TRIG 
CX3FWUPD 
MM_SNB 
MM_TRB 
MM_ACTIVATE 

Definition at line 249 of file motion-module.h.

Enumerator:
REG_UCTRL_CFG 
REG_INT_ID_CONFIG 
REG_INT_TYPE_CONFIG 
REG_EEPROM_CMD 
REG_EEPROM_DATA 
REG_TIMER_PRESCALER 
REG_TIMER_RESET_VALUE 
REG_GYRO_BYPASS_CMD1 
REG_GYRO_BYPASS_CMD2 
REG_GYRO_BYPASS_RDOUT1 
REG_GYRO_BYPASS_RDOUT2 
REG_ACC_BYPASS_CMD1 
REG_ACC_BYPASS_CMD2 
REG_ACC_BYPASS_RDOUT1 
REG_ACC_BYPASS_RDOUT2 
REG_REQ_LTR 
REG_STATUS_REG 
REG_FIFO_RD 
REG_FIRST_INT_IGNORE 
REG_IAP_REG 
REG_INT_ENABLE 
REG_CURR_PWR_STATE 
REG_NEXT_PWR_STATE 
REG_ACC_BW 
REG_GYRO_BW 
REG_ACC_RANGE 
REG_GYRO_RANGE 
REG_IMG_VER 
REG_ERROR 
REG_JUMP_TO_APP 

Definition at line 208 of file motion-module.h.

Enumerator:
accel_bw_default 
accel_bw_125hz 
accel_bw_250hz 

Definition at line 60 of file motion-module.h.

Enumerator:
accel_range_default 
accel_range_4g 
accel_range_8g 
accel_range_16g 

Definition at line 52 of file motion-module.h.

Enumerator:
gyro_bw_default 
gyro_bw_200hz 

Definition at line 46 of file motion-module.h.

Enumerator:
gyro_range_default 
gyro_range_1000 
gyro_range_2000 

Definition at line 39 of file motion-module.h.

Enumerator:
mm_output_undefined 
mm_video_output 
mm_events_output 

Definition at line 109 of file motion-module.h.

Enumerator:
mm_idle 
mm_streaming 
mm_eventing 
mm_full_load 

Definition at line 125 of file motion-module.h.

Enumerator:
imu_not_responding 
illegal_configuration 
ts_fifo_overflow 
imu_fifo_overflow 
watchdog_reset 
crc_error 
missing_data_from_imu 
bootloader_failure 
eeprom_error 
bist_check_failed 
uctrl_not_responding 
cx3_fifo_overflow 
general_cx3_failure 
cx3_usb_failure 
reserved_1 
reserved_2 
max_mm_error 

Definition at line 17 of file motion-module.h.

Enumerator:
PWR_STATE_DNR 
PWR_STATE_INIT 
PWR_STATE_ACTIVE 
PWR_STATE_PAUSE 
PWR_STATE_IAP 

Definition at line 241 of file motion-module.h.


Function Documentation

void rsimpl::motion_module::config ( uvc::device &  device,
uint8_t  gyro_bw,
uint8_t  gyro_range,
uint8_t  accel_bw,
uint8_t  accel_range,
uint32_t  time_seed 
)

Definition at line 277 of file motion-module.cpp.

const char* rsimpl::motion_module::get_mm_request_name ( mm_request  request) [inline]

Definition at line 116 of file motion-module.h.

const char* rsimpl::motion_module::get_mm_state_name ( mm_state  state) [inline]

Definition at line 133 of file motion-module.h.



librealsense
Author(s): Sergey Dorodnicov , Mark Horn , Reagan Lopez
autogenerated on Tue Jun 25 2019 19:54:41