Classes | Typedefs | Enumerations | Functions | Variables
segway Namespace Reference

Classes

struct  CrcTable
class  FaultPacking
class  Logger
class  Rmp440LEInterface
struct  RmpConfigurationCommand
class  RmpConfigurationCommandSet
class  RmpFault
class  RmpInterface
class  RmpTransport
class  RmpUdp
class  RmpUsb

Typedefs

typedef std::vector< uint8_t > Bytes
typedef std::vector< std::string > FaultDecodeList
typedef std::vector< FaultPackingFaultPackingList
typedef std::vector< std::string > FaultStatusDescription
typedef std::vector
< UserDefinedFeedbackType
FeedbackTypeList

Enumerations

enum  FaultGroup {
  TRANSIENT = 0, CRITICAL, COMM, SENSORS,
  BSA, MCU, ARCHITECTURE, INTERNAL
}
enum  LogLevel {
  DEBUG = 0, INFO, WARNING, ERROR,
  FATAL
}
enum  OperationalState {
  CCU_INIT = 0, INIT_PROPULSION, CHECK_STARTUP_ISSUES, STANDBY_MODE,
  TRACTOR_MODE, DISABLE_POWER
}
enum  RmpAudioSong {
  MOTOR_AUDIO_PLAY_NO_SONG = 0, MOTOR_AUDIO_PLAY_POWER_ON_SONG, MOTOR_AUDIO_PLAY_POWER_OFF_SONG, MOTOR_AUDIO_PLAY_ALARM_SONG,
  MOTOR_AUDIO_PLAY_MODE_UP_SONG, MOTOR_AUDIO_PLAY_MODE_DOWN_SONG, MOTOR_AUDIO_PLAY_ENTER_ALARM_SONG, MOTOR_AUDIO_PLAY_EXIT_ALARM_SONG,
  MOTOR_AUDIO_PLAY_FINAL_SHUTDOWN_SONG, MOTOR_AUDIO_PLAY_CORRECT_ISSUE, MOTOR_AUDIO_PLAY_ISSUE_CORRECTED, MOTOR_AUDIO_PLAY_CORRECT_ISSUE_REPEATING,
  MOTOR_AUDIO_PLAY_BEGINNER_ACK, MOTOR_AUDIO_PLAY_EXPERT_ACK, MOTOR_AUDIO_ENTER_FOLLOW, MOTOR_AUDIO_TEST_SWEEP,
  MOTOR_AUDIO_SIMULATE_MOTOR_NOISE
}
enum  RmpConfigurationCommandId {
  CONFIG_CMD_ID_NONE = 0, CONFIG_CMD_ID_SET_MAXIMUM_VELOCITY, CONFIG_CMD_ID_SET_MAXIMUM_ACCELERATION, CONFIG_CMD_ID_SET_MAXIMUM_DECELERATION,
  CONFIG_CMD_ID_SET_DTZ_DECEL_RATE, CONFIG_CMD_ID_SET_COASTDOAN_ACCEL, CONFIG_CMD_ID_SET_MAXIMUM_TURN_RATE, CONFIG_CMD_ID_SET_MAXIMUM_TURN_ACCEL,
  CONFIG_CMD_ID_SET_TIRE_DIAMETER, CONFIG_CMD_ID_SET_WHEEL_BASE_LENGTH, CONFIG_CMD_ID_SET_WHEEL_TRACK_WIDTH, CONFIG_CMD_ID_SET_TRANSMISSION_RATIO,
  CONFIG_CMD_ID_SET_INPUT_CONFIG_BITMAP, CONFIG_CMD_ID_SET_ETH_IP_ADDRESS, CONFIG_CMD_ID_SET_ETH_PORT_NUMBER, CONFIG_CMD_ID_SET_ETH_SUBNET_MASK,
  CONFIG_CMD_ID_SET_GATEWAY, CONFIG_CMD_ID_SET_USER_FB_1_BITMAP, CONFIG_CMD_ID_SET_USER_FB_2_BITMAP, CONFIG_CMD_ID_SET_USER_FB_3_BITMAP,
  CONFIG_CMD_ID_SET_USER_FB_4_BITMAP, CONFIG_CMD_ID_FORCE_CONFIG_FEEDBACK_BITMAPS = 30, CONFIG_CMD_ID_SET_AUDIO_COMMAND, CONFIG_CMD_ID_SET_OPERATIONAL_MODE,
  CONFIG_CMD_ID_SEND_SP_FAULT_LOG, CONFIG_CMD_ID_RESET_INTEGRATORS, CONFIG_CMD_ID_RESET_PARAMS_TO_DEFAULT
}
enum  RmpMessageId { STANDARD_MOTION = 0x500, CONFIGURATION_CMD, CAN_RMP_RESP, OMNI_MOTION = 0x600 }
enum  RmpOperationalModeRequest {
  DISABLE_REQUEST = 1, POWERDOWN_REQUEST, DTZ_REQUEST, STANDBY_REQUEST,
  TRACTOR_REQUEST
}
enum  RmpResetIntegrator {
  RESET_LINEAR_POSITION = 0x00000001, RESET_RIGHT_FRONT_POSITION = 0x00000002, RESET_LEFT_FRONT_POSITION = 0x00000004, RESET_RIGHT_REAR_POSITION = 0x00000008,
  RESET_LEFT_REAR_POSITION = 0x00000010, RESET_ALL_POSITION_DATA = 0x0000001F
}
enum  UserDefinedFeedbackBitmapType { USER_DEFINED_FEEDBACK_BITMAP_1 = 0, USER_DEFINED_FEEDBACK_BITMAP_2, USER_DEFINED_FEEDBACK_BITMAP_3, USER_DEFINED_FEEDBACK_BITMAP_4 }
enum  UserDefinedFeedbackType {
  NO_FEEDBACK = 0xFFFFFFFF, INVALID_FEEDBACK = 0xFFFFFFFE, FAULT_STATUS_WORD_1 = 0, FAULT_STATUS_WORD_2,
  FAULT_STATUS_WORD_3, FAULT_STATUS_WORD_4, MCU_0_FAULT_STATUS, MCU_1_FAULT_STATUS,
  MCU_2_FAULT_STATUS, MCU_3_FAULT_STATUS, FRAME_COUNT, OPERATIONAL_STATE,
  DYNAMIC_RESPONSE, MIN_PROPULSION_BATT_SOC, AUX_BATT_SOC, INERTIAL_X_ACC_G,
  INERTIAL_Y_ACC_G, INERTIAL_X_RATE_RPS, INERTIAL_Y_RATE_RPS, INERTIAL_Z_RATE_RPS,
  PSE_PITCH_DEG, PSE_PITCH_RATE_DPS, PSE_ROLL_DEG, PSE_ROLL_RATE_DPS,
  PSE_YAW_RATE_DPS, PSE_DATA_IS_VALID, YAW_RATE_LIMIT_RPS, VEL_LIMIT_MPS,
  LINEAR_ACCEL_MSP2, LINEAR_VEL_MPS, DIFFERENTIAL_WHEEL_VEL_RPS, RIGHT_FRONT_VEL_MPS,
  LEFT_FRONT_VEL_MPS, RIGHT_REAR_VEL_MPS, LEFT_REAR_VEL_MPS, RIGHT_FRONT_POS_M,
  LEFT_FRONT_POS_M, RIGHT_REAR_POS_M, LEFT_REAR_POS_M, LINEAR_POS_M,
  RIGHT_FRONT_CURRENT_A0PK, LEFT_FRONT_CURRENT_A0PK, RIGHT_REAR_CURRENT_A0PK, LEFT_REAR_CURRENT_A0PK,
  MAX_MOTOR_CURRENT_A0PK, RIGHT_FRONT_CURRENT_LIMIT_A0PK, LEFT_FRONT_CURRENT_LIMIT_A0PK, RIGHT_REAR_CURRENT_LIMIT_A0PK,
  LEFT_REAR_CURRENT_LIMIT_A0PK, MIN_MOTOR_CURRENT_LIMIT_A0PK, FRONT_BASE_BATT_1_SOC, FRONT_BASE_BATT_2_SOC,
  REAR_BASE_BATT_1_SOC, REAR_BASE_BATT_2_SOC, FRONT_BASE_BATT_1_TEMP_DEGC, FRONT_BASE_BATT_2_TEMP_DEGC,
  REAR_BASE_BATT_1_TEMP_DEGC, REAR_BASE_BATT_2_TEMP_DEGC, VEL_TARGET_MPS, YAW_RATE_TARGET_RPS,
  ANGLE_TARGET_DEG, AUX_BATT_VOLTAGE_V, AUX_BATT_CURRENT_A, AUX_BATT_TEMP_DEGC,
  ABB_SYSTEM_STATUS, AUX_BATT_STATUS, AUX_BATT_FAULTS, P72V_BATTERY_VOLTAGE,
  SP_SW_BUILD_ID, UIP_SW_BUILD_ID, MCU_0_INST_POWER_W, MCU_1_INST_POWER_W,
  MCU_2_INST_POWER_W, MCU_3_INST_POWER_W, MCU_0_TOTAL_ENERGY_WH, MCU_1_TOTAL_ENERGY_WH,
  MCU_2_TOTAL_ENERGY_WH, MCU_3_TOTAL_ENERGY_WH, FRAM_VEL_LIMIT_MPS, FRAM_ACCEL_LIMIT_MPS2,
  FRAM_DECEL_LIMIT_MPS2, FRAM_DTZ_DECEL_LIMIT_MPS2, FRAM_COASTDOWN_DECEL_MPS2, FRAM_YAW_RATE_LIMIT_RPS,
  FRAM_YAW_ACCEL_LIMIT_RPS2, FRAM_TIRE_DIAMETER_M, FRAM_WHEEL_BASE_LENGTH_M, FRAM_WHEEL_TRACK_WIDTH_M,
  FRAM_TRANSMISSION_RATIO, FRAM_CONFIG_BITMAP, FRAM_ETH_IP_ADDRESS, FRAM_ETH_PORT_NUMBER,
  FRAM_ETH_SUBNET_MASK, FRAM_ETH_GATEWAY, USER_FEEDBACK_BITMAP_1, USER_FEEDBACK_BITMAP_2,
  USER_FEEDBACK_BITMAP_3, USER_FEEDBACK_BITMAP_4
}

Functions

void AppendCrc16 (Bytes &rBytes)
uint16_t ConvertBytesToUint16 (const uint8_t *pByte, size_t size)
uint32_t ConvertBytesToUint32 (const uint8_t *pByte, size_t size)
void ConvertCommandToBytes (uint16_t commandId, uint32_t value1, uint32_t value2, Bytes &rBytes)
uint32_t ConvertFloatToUint32 (float data)
void ConvertUint16ToBytes (const uint16_t &rData, uint8_t *pByte, size_t size)
void ConvertUint32ToBytes (const uint32_t &rData, uint8_t *pByte, size_t size)
float ConvertUint32ToFloat (uint32_t data)
uint16_t GetCrc (Bytes &rBytes, size_t size)
std::string GetLogLevelString (LogLevel level)
void InitializeFaultDecodeList (FaultDecodeList &rDecodeList, unsigned int argumentCount,...)
bool IsCrcValid (Bytes &rBytes, size_t size)

Variables

static const unsigned int BAUD_RATE = 115200
static const unsigned int CHARACTER_SIZE = 8
static const uint16_t CRC_ADJUSTMENT = 0xA001
static const size_t CRC_FEEDBACK_SIZE = sizeof(uint32_t)
static const size_t CRC_SIZE = sizeof(uint16_t)
static const size_t CRC_TABLE_SIZE = 256
static const size_t FEEDBACK_TYPE_NBR = 4
static const size_t FORCE_CONFIG_FEEDBACK_1_IDX = 16
static const size_t FORCE_CONFIG_FEEDBACK_2_IDX = 17
static const size_t FORCE_CONFIG_FEEDBACK_3_IDX = 18
static const size_t FORCE_CONFIG_FEEDBACK_4_IDX = 19
static const size_t MAX_ENTRIES_PER_FEEDBACK = 32
static const size_t MAX_FEEDBACK_ENTRIES = FEEDBACK_TYPE_NBR * MAX_ENTRIES_PER_FEEDBACK
static const size_t MAX_RCV_SIZE = 1024
static const size_t MAX_TRIAL_NBR = 7
static const uint32_t NO_FAULT = 0x00000000
static const size_t NVM_CONFIG_PARAM_NBR = 20
static const size_t NVM_CONFIG_PARAM_SIZE = NVM_CONFIG_PARAM_NBR * sizeof(uint32_t)
static const uint32_t PSE1_VALID = 0x00000001
static const uint32_t PSE2_VALID = 0x00000002
static const uint32_t PSE_VALID = PSE1_VALID | PSE2_VALID
static const size_t RMP_CMD_BODY_SIZE = sizeof(uint16_t) + 2 * sizeof(uint32_t)
static const size_t RMP_CMD_HEADER_IDX = 0
static const size_t RMP_CMD_VAL1_IDX = sizeof(uint16_t)
static const size_t RMP_CMD_VAL2_IDX = sizeof(uint16_t) + sizeof(uint32_t)
static boost::mutex s_Mutex
static const long TIMEOUT = 30

Detailed Description

Please read the rmp user manual (for instance, page 53 of the RMP 440LE manual)


Typedef Documentation

typedef std::vector<uint8_t> segway::Bytes

Definition at line 46 of file RmpType.h.

typedef std::vector<std::string> segway::FaultDecodeList

Definition at line 158 of file RmpFault.h.

typedef std::vector<FaultPacking> segway::FaultPackingList

Definition at line 156 of file RmpFault.h.

typedef std::vector<std::string> segway::FaultStatusDescription

Definition at line 53 of file RmpFault.h.

Definition at line 157 of file RmpFault.h.


Enumeration Type Documentation

Define fault group type Please read the rmp user manual (for instance, page 73 of the RMP 440LE manual)

Enumerator:
TRANSIENT 
CRITICAL 
COMM 
SENSORS 
BSA 
MCU 
ARCHITECTURE 
INTERNAL 

Definition at line 59 of file RmpFault.h.

Descibe the severity level of the log

Enumerator:
DEBUG 
INFO 
WARNING 
ERROR 
FATAL 

Definition at line 52 of file RmpLogger.h.

Define Operational States Please read the rmp user manual (for instance, page 61 of the RMP 440LE manual)

Enumerator:
CCU_INIT 
INIT_PROPULSION 
CHECK_STARTUP_ISSUES 
STANDBY_MODE 
TRACTOR_MODE 
DISABLE_POWER 

Definition at line 79 of file RmpUserDefinedFeedbackType.h.

Define Audio Songs Please read the rmp user manual (for instance, page 51 of the RMP 440LE manual)

Enumerator:
MOTOR_AUDIO_PLAY_NO_SONG 
MOTOR_AUDIO_PLAY_POWER_ON_SONG 
MOTOR_AUDIO_PLAY_POWER_OFF_SONG 
MOTOR_AUDIO_PLAY_ALARM_SONG 
MOTOR_AUDIO_PLAY_MODE_UP_SONG 
MOTOR_AUDIO_PLAY_MODE_DOWN_SONG 
MOTOR_AUDIO_PLAY_ENTER_ALARM_SONG 
MOTOR_AUDIO_PLAY_EXIT_ALARM_SONG 
MOTOR_AUDIO_PLAY_FINAL_SHUTDOWN_SONG 
MOTOR_AUDIO_PLAY_CORRECT_ISSUE 
MOTOR_AUDIO_PLAY_ISSUE_CORRECTED 
MOTOR_AUDIO_PLAY_CORRECT_ISSUE_REPEATING 
MOTOR_AUDIO_PLAY_BEGINNER_ACK 
MOTOR_AUDIO_PLAY_EXPERT_ACK 
MOTOR_AUDIO_ENTER_FOLLOW 
MOTOR_AUDIO_TEST_SWEEP 
MOTOR_AUDIO_SIMULATE_MOTOR_NOISE 

Definition at line 98 of file RmpConfigurationCommand.h.

Define Rmp Configuration Command Ids Please read the rmp user manual (for instance, page 53 of the RMP 440LE manual)

Enumerator:
CONFIG_CMD_ID_NONE 
CONFIG_CMD_ID_SET_MAXIMUM_VELOCITY 
CONFIG_CMD_ID_SET_MAXIMUM_ACCELERATION 
CONFIG_CMD_ID_SET_MAXIMUM_DECELERATION 
CONFIG_CMD_ID_SET_DTZ_DECEL_RATE 
CONFIG_CMD_ID_SET_COASTDOAN_ACCEL 
CONFIG_CMD_ID_SET_MAXIMUM_TURN_RATE 
CONFIG_CMD_ID_SET_MAXIMUM_TURN_ACCEL 
CONFIG_CMD_ID_SET_TIRE_DIAMETER 
CONFIG_CMD_ID_SET_WHEEL_BASE_LENGTH 
CONFIG_CMD_ID_SET_WHEEL_TRACK_WIDTH 
CONFIG_CMD_ID_SET_TRANSMISSION_RATIO 
CONFIG_CMD_ID_SET_INPUT_CONFIG_BITMAP 
CONFIG_CMD_ID_SET_ETH_IP_ADDRESS 
CONFIG_CMD_ID_SET_ETH_PORT_NUMBER 
CONFIG_CMD_ID_SET_ETH_SUBNET_MASK 
CONFIG_CMD_ID_SET_GATEWAY 
CONFIG_CMD_ID_SET_USER_FB_1_BITMAP 
CONFIG_CMD_ID_SET_USER_FB_2_BITMAP 
CONFIG_CMD_ID_SET_USER_FB_3_BITMAP 
CONFIG_CMD_ID_SET_USER_FB_4_BITMAP 
CONFIG_CMD_ID_FORCE_CONFIG_FEEDBACK_BITMAPS 
CONFIG_CMD_ID_SET_AUDIO_COMMAND 
CONFIG_CMD_ID_SET_OPERATIONAL_MODE 
CONFIG_CMD_ID_SEND_SP_FAULT_LOG 
CONFIG_CMD_ID_RESET_INTEGRATORS 
CONFIG_CMD_ID_RESET_PARAMS_TO_DEFAULT 

Definition at line 50 of file RmpConfigurationCommand.h.

Define Rmp Message Ids Please read the rmp user manual (for instance, page 38 of the RMP 440LE manual)

Enumerator:
STANDARD_MOTION 
CONFIGURATION_CMD 
CAN_RMP_RESP 
OMNI_MOTION 

Definition at line 48 of file RmpMessage.h.

Define Rmp Operational Mode Requests Please read the rmp user manual (for instance, page 51 of the RMP 440LE manual)

Enumerator:
DISABLE_REQUEST 
POWERDOWN_REQUEST 
DTZ_REQUEST 
STANDBY_REQUEST 
TRACTOR_REQUEST 

Definition at line 85 of file RmpConfigurationCommand.h.

Define Reset Integrator Bitmaps Please read the rmp user manual (for instance, page 52 of the RMP 440LE manual)

Enumerator:
RESET_LINEAR_POSITION 
RESET_RIGHT_FRONT_POSITION 
RESET_LEFT_FRONT_POSITION 
RESET_RIGHT_REAR_POSITION 
RESET_LEFT_REAR_POSITION 
RESET_ALL_POSITION_DATA 

Definition at line 123 of file RmpConfigurationCommand.h.

Define User Defined Feedback Bitmap Types Please read the rmp user manual (for instance, page 53 of the RMP 440LE manual)

Enumerator:
USER_DEFINED_FEEDBACK_BITMAP_1 
USER_DEFINED_FEEDBACK_BITMAP_2 
USER_DEFINED_FEEDBACK_BITMAP_3 
USER_DEFINED_FEEDBACK_BITMAP_4 

Definition at line 67 of file RmpUserDefinedFeedbackType.h.

Define User Defined Feedback Types Please read the rmp user manual (for instance, page 61 of the RMP 440LE manual)

Enumerator:
NO_FEEDBACK 
INVALID_FEEDBACK 
FAULT_STATUS_WORD_1 
FAULT_STATUS_WORD_2 
FAULT_STATUS_WORD_3 
FAULT_STATUS_WORD_4 
MCU_0_FAULT_STATUS 
MCU_1_FAULT_STATUS 
MCU_2_FAULT_STATUS 
MCU_3_FAULT_STATUS 
FRAME_COUNT 
OPERATIONAL_STATE 
DYNAMIC_RESPONSE 
MIN_PROPULSION_BATT_SOC 
AUX_BATT_SOC 
INERTIAL_X_ACC_G 
INERTIAL_Y_ACC_G 
INERTIAL_X_RATE_RPS 
INERTIAL_Y_RATE_RPS 
INERTIAL_Z_RATE_RPS 
PSE_PITCH_DEG 
PSE_PITCH_RATE_DPS 
PSE_ROLL_DEG 
PSE_ROLL_RATE_DPS 
PSE_YAW_RATE_DPS 
PSE_DATA_IS_VALID 
YAW_RATE_LIMIT_RPS 
VEL_LIMIT_MPS 
LINEAR_ACCEL_MSP2 
LINEAR_VEL_MPS 
DIFFERENTIAL_WHEEL_VEL_RPS 
RIGHT_FRONT_VEL_MPS 
LEFT_FRONT_VEL_MPS 
RIGHT_REAR_VEL_MPS 
LEFT_REAR_VEL_MPS 
RIGHT_FRONT_POS_M 
LEFT_FRONT_POS_M 
RIGHT_REAR_POS_M 
LEFT_REAR_POS_M 
LINEAR_POS_M 
RIGHT_FRONT_CURRENT_A0PK 
LEFT_FRONT_CURRENT_A0PK 
RIGHT_REAR_CURRENT_A0PK 
LEFT_REAR_CURRENT_A0PK 
MAX_MOTOR_CURRENT_A0PK 
RIGHT_FRONT_CURRENT_LIMIT_A0PK 
LEFT_FRONT_CURRENT_LIMIT_A0PK 
RIGHT_REAR_CURRENT_LIMIT_A0PK 
LEFT_REAR_CURRENT_LIMIT_A0PK 
MIN_MOTOR_CURRENT_LIMIT_A0PK 
FRONT_BASE_BATT_1_SOC 
FRONT_BASE_BATT_2_SOC 
REAR_BASE_BATT_1_SOC 
REAR_BASE_BATT_2_SOC 
FRONT_BASE_BATT_1_TEMP_DEGC 
FRONT_BASE_BATT_2_TEMP_DEGC 
REAR_BASE_BATT_1_TEMP_DEGC 
REAR_BASE_BATT_2_TEMP_DEGC 
VEL_TARGET_MPS 
YAW_RATE_TARGET_RPS 
ANGLE_TARGET_DEG 
AUX_BATT_VOLTAGE_V 
AUX_BATT_CURRENT_A 
AUX_BATT_TEMP_DEGC 
ABB_SYSTEM_STATUS 
AUX_BATT_STATUS 
AUX_BATT_FAULTS 
P72V_BATTERY_VOLTAGE 
SP_SW_BUILD_ID 
UIP_SW_BUILD_ID 
MCU_0_INST_POWER_W 
MCU_1_INST_POWER_W 
MCU_2_INST_POWER_W 
MCU_3_INST_POWER_W 
MCU_0_TOTAL_ENERGY_WH 
MCU_1_TOTAL_ENERGY_WH 
MCU_2_TOTAL_ENERGY_WH 
MCU_3_TOTAL_ENERGY_WH 
FRAM_VEL_LIMIT_MPS 
FRAM_ACCEL_LIMIT_MPS2 
FRAM_DECEL_LIMIT_MPS2 
FRAM_DTZ_DECEL_LIMIT_MPS2 
FRAM_COASTDOWN_DECEL_MPS2 
FRAM_YAW_RATE_LIMIT_RPS 
FRAM_YAW_ACCEL_LIMIT_RPS2 
FRAM_TIRE_DIAMETER_M 
FRAM_WHEEL_BASE_LENGTH_M 
FRAM_WHEEL_TRACK_WIDTH_M 
FRAM_TRANSMISSION_RATIO 
FRAM_CONFIG_BITMAP 
FRAM_ETH_IP_ADDRESS 
FRAM_ETH_PORT_NUMBER 
FRAM_ETH_SUBNET_MASK 
FRAM_ETH_GATEWAY 
USER_FEEDBACK_BITMAP_1 
USER_FEEDBACK_BITMAP_2 
USER_FEEDBACK_BITMAP_3 
USER_FEEDBACK_BITMAP_4 

Definition at line 93 of file RmpUserDefinedFeedbackType.h.


Function Documentation

void segway::AppendCrc16 ( Bytes &  rBytes) [inline]

Append checksum at the end of byte vector

Parameters:
rBytesbyte vector

Definition at line 245 of file RmpHelper.h.

uint16_t segway::ConvertBytesToUint16 ( const uint8_t *  pByte,
size_t  size 
) [inline]

Convert a byte array to a 16 bits unsigned integer

Parameters:
pBytebyte array
sizesize of the array
Returns:
16 bits unsigned integer

Definition at line 94 of file RmpHelper.h.

uint32_t segway::ConvertBytesToUint32 ( const uint8_t *  pByte,
size_t  size 
) [inline]

Convert a byte array to a 32 bits unsigned integer

Parameters:
pBytebyte array
sizesize of the array
Returns:
32 bits unsigned integer

Definition at line 108 of file RmpHelper.h.

void segway::ConvertCommandToBytes ( uint16_t  commandId,
uint32_t  value1,
uint32_t  value2,
Bytes &  rBytes 
) [inline]

Convert a rmp command to a byte vector

Parameters:
commandIdcommand id
value1first value
value2second value
rBytesreturned byte vector

Definition at line 145 of file RmpHelper.h.

uint32_t segway::ConvertFloatToUint32 ( float  data) [inline]

Convert a float to a 32 bits unsigned integer

Parameters:
datafloat
Returns:
32 bits unsigned integer

Definition at line 123 of file RmpHelper.h.

void segway::ConvertUint16ToBytes ( const uint16_t &  rData,
uint8_t *  pByte,
size_t  size 
) [inline]

Convert a 16 bits unsigned integer to a byte array

Parameters:
rDatadata to convert
pBytebyte array (should already be allocated)
sizesize of the array

Definition at line 64 of file RmpHelper.h.

void segway::ConvertUint32ToBytes ( const uint32_t &  rData,
uint8_t *  pByte,
size_t  size 
) [inline]

Convert a 32 bits unsigned integer to a byte array

Parameters:
rDatadata to convert
pBytebyte array (should already be allocated)
sizesize of the array

Definition at line 78 of file RmpHelper.h.

float segway::ConvertUint32ToFloat ( uint32_t  data) [inline]

Convert a 32 bits unsigned integer to a float

Parameters:
data32 bits unsigned integer
Returns:
float

Definition at line 133 of file RmpHelper.h.

uint16_t segway::GetCrc ( Bytes &  rBytes,
size_t  size 
) [inline]

Compute the checksum of a byte vector

Parameters:
rBytesbyte vector
sizenumber of bytes to check
Returns:
crc value

Definition at line 224 of file RmpHelper.h.

std::string segway::GetLogLevelString ( LogLevel  level)

Definition at line 167 of file RmpLogger.cpp.

void segway::InitializeFaultDecodeList ( FaultDecodeList &  rDecodeList,
unsigned int  argumentCount,
  ... 
)

Definition at line 47 of file RmpFault.cpp.

bool segway::IsCrcValid ( Bytes &  rBytes,
size_t  size 
) [inline]

Check data integrity

Parameters:
rBytesbyte vector
sizesize of the data to check
Returns:
wether the Crc values matche

Definition at line 261 of file RmpHelper.h.


Variable Documentation

const unsigned int segway::BAUD_RATE = 115200 [static]

Definition at line 54 of file RmpUsb.cpp.

const unsigned int segway::CHARACTER_SIZE = 8 [static]

Definition at line 55 of file RmpUsb.cpp.

const uint16_t segway::CRC_ADJUSTMENT = 0xA001 [static]

Definition at line 54 of file RmpHelper.h.

const size_t segway::CRC_FEEDBACK_SIZE = sizeof(uint32_t) [static]

Definition at line 56 of file RmpHelper.h.

const size_t segway::CRC_SIZE = sizeof(uint16_t) [static]

Definition at line 55 of file RmpHelper.h.

const size_t segway::CRC_TABLE_SIZE = 256 [static]

Definition at line 53 of file RmpHelper.h.

const size_t segway::FEEDBACK_TYPE_NBR = 4 [static]

Definition at line 47 of file RmpUserDefinedFeedbackType.h.

const size_t segway::FORCE_CONFIG_FEEDBACK_1_IDX = 16 [static]

Definition at line 54 of file RmpUserDefinedFeedbackType.h.

const size_t segway::FORCE_CONFIG_FEEDBACK_2_IDX = 17 [static]

Definition at line 55 of file RmpUserDefinedFeedbackType.h.

const size_t segway::FORCE_CONFIG_FEEDBACK_3_IDX = 18 [static]

Definition at line 56 of file RmpUserDefinedFeedbackType.h.

const size_t segway::FORCE_CONFIG_FEEDBACK_4_IDX = 19 [static]

Definition at line 57 of file RmpUserDefinedFeedbackType.h.

const size_t segway::MAX_ENTRIES_PER_FEEDBACK = 32 [static]

Definition at line 48 of file RmpUserDefinedFeedbackType.h.

Definition at line 49 of file RmpUserDefinedFeedbackType.h.

static const size_t segway::MAX_RCV_SIZE = 1024 [static]

Definition at line 58 of file RmpUdp.cpp.

const size_t segway::MAX_TRIAL_NBR = 7 [static]

Definition at line 56 of file RmpInterface.cpp.

const uint32_t segway::NO_FAULT = 0x00000000 [static]

Definition at line 51 of file RmpFault.h.

const size_t segway::NVM_CONFIG_PARAM_NBR = 20 [static]

Definition at line 51 of file RmpUserDefinedFeedbackType.h.

const size_t segway::NVM_CONFIG_PARAM_SIZE = NVM_CONFIG_PARAM_NBR * sizeof(uint32_t) [static]

Definition at line 52 of file RmpUserDefinedFeedbackType.h.

const uint32_t segway::PSE1_VALID = 0x00000001 [static]

Definition at line 59 of file RmpUserDefinedFeedbackType.h.

const uint32_t segway::PSE2_VALID = 0x00000002 [static]

Definition at line 60 of file RmpUserDefinedFeedbackType.h.

const uint32_t segway::PSE_VALID = PSE1_VALID | PSE2_VALID [static]

Definition at line 61 of file RmpUserDefinedFeedbackType.h.

const size_t segway::RMP_CMD_BODY_SIZE = sizeof(uint16_t) + 2 * sizeof(uint32_t) [static]

Definition at line 48 of file RmpHelper.h.

const size_t segway::RMP_CMD_HEADER_IDX = 0 [static]

Definition at line 49 of file RmpHelper.h.

const size_t segway::RMP_CMD_VAL1_IDX = sizeof(uint16_t) [static]

Definition at line 50 of file RmpHelper.h.

const size_t segway::RMP_CMD_VAL2_IDX = sizeof(uint16_t) + sizeof(uint32_t) [static]

Definition at line 51 of file RmpHelper.h.

boost::mutex segway::s_Mutex [static]

Definition at line 50 of file RmpLogger.cpp.

static const long segway::TIMEOUT = 30 [static]

Definition at line 59 of file RmpUdp.cpp.



rmp_base
Author(s):
autogenerated on Wed Aug 26 2015 16:24:40