Classes | Defines | Typedefs | Enumerations | Functions
phidget21.h File Reference

Go to the source code of this file.

Classes

struct  _CPhidget_Timestamp
struct  _CPhidgetIR_CodeInfo
struct  _CPhidgetSpatial_SpatialEventData
struct  GPGGA
struct  GPGSA
struct  GPGSV
struct  GPRMC
struct  GPSDate
struct  GPSSatInfo
struct  GPSTime
struct  GPVTG
struct  NMEAData

Defines

#define CCONV
#define CPHIDGET_CONSTANTS
#define PFALSE   0x00
#define PTRUE   0x01
Phidget States

Returned by getStatus() functions

#define PHIDGET_ATTACHED   0x1
#define PHIDGET_NOTATTACHED   0x0
Phidget Error Codes

Returned by all C API calls

#define PHIDGET_ERROR_CODE_COUNT   20
#define EPHIDGET_OK   0
#define EPHIDGET_NOTFOUND   1
#define EPHIDGET_NOMEMORY   2
#define EPHIDGET_UNEXPECTED   3
#define EPHIDGET_INVALIDARG   4
#define EPHIDGET_NOTATTACHED   5
#define EPHIDGET_INTERRUPTED   6
#define EPHIDGET_INVALID   7
#define EPHIDGET_NETWORK   8
#define EPHIDGET_UNKNOWNVAL   9
#define EPHIDGET_BADPASSWORD   10
#define EPHIDGET_UNSUPPORTED   11
#define EPHIDGET_DUPLICATE   12
#define EPHIDGET_TIMEOUT   13
#define EPHIDGET_OUTOFBOUNDS   14
#define EPHIDGET_EVENT   15
#define EPHIDGET_NETWORK_NOTCONNECTED   16
#define EPHIDGET_WRONGDEVICE   17
#define EPHIDGET_CLOSED   18
#define EPHIDGET_BADVERSION   19
Phidget Error Event Codes

Returned in the Phidget error event

#define EEPHIDGET_EVENT_ERROR(code)   (0x8000 + code)
#define EEPHIDGET_NETWORK   EEPHIDGET_EVENT_ERROR(0x0001)
#define EEPHIDGET_BADPASSWORD   EEPHIDGET_EVENT_ERROR(0x0002)
#define EEPHIDGET_BADVERSION   EEPHIDGET_EVENT_ERROR(0x0003)
#define EEPHIDGET_OK   EEPHIDGET_EVENT_ERROR(0x1000)
#define EEPHIDGET_OVERRUN   EEPHIDGET_EVENT_ERROR(0x1002)
#define EEPHIDGET_PACKETLOST   EEPHIDGET_EVENT_ERROR(0x1003)
#define EEPHIDGET_WRAP   EEPHIDGET_EVENT_ERROR(0x1004)
#define EEPHIDGET_OVERTEMP   EEPHIDGET_EVENT_ERROR(0x1005)
#define EEPHIDGET_OVERCURRENT   EEPHIDGET_EVENT_ERROR(0x1006)
#define EEPHIDGET_OUTOFRANGE   EEPHIDGET_EVENT_ERROR(0x1007)
#define EEPHIDGET_BADPOWER   EEPHIDGET_EVENT_ERROR(0x1008)
Phidget Unknown Constants

Data values will be set to these constants when a call fails with EPHIDGET_UNKNOWNVAL.

#define PUNK_BOOL   0x02
#define PUNK_SHRT   0x7FFF
#define PUNK_INT   0x7FFFFFFF
#define PUNK_INT64   0x7FFFFFFFFFFFFFFFLL
#define PUNK_DBL   1e300
#define PUNK_FLT   1e30

Typedefs

typedef long long __int64
typedef struct _CPhidget_Timestamp CPhidget_Timestamp
typedef struct
_CPhidget_Timestamp
CPhidget_TimestampHandle
typedef struct
_CPhidgetAccelerometer * 
CPhidgetAccelerometerHandle
typedef struct
_CPhidgetAdvancedServo * 
CPhidgetAdvancedServoHandle
typedef struct _CPhidgetAnalog * CPhidgetAnalogHandle
typedef struct _CPhidgetBridge * CPhidgetBridgeHandle
typedef int(* CPhidgetDictionary_OnKeyChange_Function )(CPhidgetDictionaryHandle dict, void *userPtr, const char *key, const char *value, CPhidgetDictionary_keyChangeReason reason)
typedef struct
_CPhidgetDictionary * 
CPhidgetDictionaryHandle
typedef struct
_CPhidgetDictionaryListener * 
CPhidgetDictionaryListenerHandle
typedef struct _CPhidgetEncoder * CPhidgetEncoderHandle
typedef struct
_CPhidgetFrequencyCounter * 
CPhidgetFrequencyCounterHandle
typedef struct _CPhidgetGPS * CPhidgetGPSHandle
typedef struct _CPhidget * CPhidgetHandle
typedef struct
_CPhidgetInterfaceKit * 
CPhidgetInterfaceKitHandle
typedef struct _CPhidgetIR_CodeInfo CPhidgetIR_CodeInfo
typedef struct
_CPhidgetIR_CodeInfo
CPhidgetIR_CodeInfoHandle
typedef struct _CPhidgetIR * CPhidgetIRHandle
typedef struct _CPhidgetLED * CPhidgetLEDHandle
typedef struct _CPhidgetManager * CPhidgetManagerHandle
typedef struct
_CPhidgetMotorControl * 
CPhidgetMotorControlHandle
typedef struct _CPhidgetPHSensor * CPhidgetPHSensorHandle
typedef struct _CPhidgetRFID * CPhidgetRFIDHandle
typedef struct _CPhidgetServo * CPhidgetServoHandle
typedef struct
_CPhidgetSpatial_SpatialEventData 
CPhidgetSpatial_SpatialEventData
typedef struct
_CPhidgetSpatial_SpatialEventData
CPhidgetSpatial_SpatialEventDataHandle
typedef struct _CPhidgetSpatial * CPhidgetSpatialHandle
typedef struct _CPhidgetStepper * CPhidgetStepperHandle
typedef struct
_CPhidgetTemperatureSensor * 
CPhidgetTemperatureSensorHandle
typedef struct _CPhidgetTextLCD * CPhidgetTextLCDHandle
typedef struct _CPhidgetTextLED * CPhidgetTextLEDHandle
typedef struct
_CPhidgetWeightSensor * 
CPhidgetWeightSensorHandle

Enumerations

enum  CPhidget_DeviceClass {
  PHIDCLASS_ACCELEROMETER = 2, PHIDCLASS_ADVANCEDSERVO = 3, PHIDCLASS_ANALOG = 22, PHIDCLASS_BRIDGE = 23,
  PHIDCLASS_ENCODER = 4, PHIDCLASS_FREQUENCYCOUNTER = 21, PHIDCLASS_GPS = 5, PHIDCLASS_INTERFACEKIT = 7,
  PHIDCLASS_IR = 19, PHIDCLASS_LED = 8, PHIDCLASS_MOTORCONTROL = 9, PHIDCLASS_PHSENSOR = 10,
  PHIDCLASS_RFID = 11, PHIDCLASS_SERVO = 12, PHIDCLASS_SPATIAL = 20, PHIDCLASS_STEPPER = 13,
  PHIDCLASS_TEMPERATURESENSOR = 14, PHIDCLASS_TEXTLCD = 15, PHIDCLASS_TEXTLED = 16, PHIDCLASS_WEIGHTSENSOR = 17
}
enum  CPhidget_DeviceID {
  PHIDID_ACCELEROMETER_3AXIS = 0x07E, PHIDID_ADVANCEDSERVO_1MOTOR = 0x082, PHIDID_ADVANCEDSERVO_8MOTOR = 0x03A, PHIDID_ANALOG_4OUTPUT = 0x037,
  PHIDID_BIPOLAR_STEPPER_1MOTOR = 0x07B, PHIDID_BRIDGE_4INPUT = 0x03B, PHIDID_ENCODER_1ENCODER_1INPUT = 0x04B, PHIDID_ENCODER_HS_1ENCODER = 0x080,
  PHIDID_ENCODER_HS_4ENCODER_4INPUT = 0x04F, PHIDID_FREQUENCYCOUNTER_2INPUT = 0x035, PHIDID_GPS = 0x079, PHIDID_INTERFACEKIT_0_0_4 = 0x040,
  PHIDID_INTERFACEKIT_0_0_8 = 0x081, PHIDID_INTERFACEKIT_0_16_16 = 0x044, PHIDID_INTERFACEKIT_2_2_2 = 0x036, PHIDID_INTERFACEKIT_8_8_8 = 0x045,
  PHIDID_INTERFACEKIT_8_8_8_w_LCD = 0x07D, PHIDID_IR = 0x04D, PHIDID_LED_64_ADV = 0x04C, PHIDID_LINEAR_TOUCH = 0x076,
  PHIDID_MOTORCONTROL_1MOTOR = 0x03E, PHIDID_MOTORCONTROL_HC_2MOTOR = 0x059, PHIDID_RFID_2OUTPUT = 0x031, PHIDID_ROTARY_TOUCH = 0x077,
  PHIDID_SPATIAL_ACCEL_3AXIS = 0x07F, PHIDID_SPATIAL_ACCEL_GYRO_COMPASS = 0x033, PHIDID_TEMPERATURESENSOR = 0x070, PHIDID_TEMPERATURESENSOR_4 = 0x032,
  PHIDID_TEMPERATURESENSOR_IR = 0x03C, PHIDID_TEXTLCD_2x20_w_8_8_8 = 0x17D, PHIDID_TEXTLCD_ADAPTER = 0x03D, PHIDID_UNIPOLAR_STEPPER_4MOTOR = 0x07A,
  PHIDID_ACCELEROMETER_2AXIS = 0x071, PHIDID_INTERFACEKIT_0_8_8_w_LCD = 0x053, PHIDID_INTERFACEKIT_4_8_8 = 4, PHIDID_LED_64 = 0x04A,
  PHIDID_MOTORCONTROL_LV_2MOTOR_4INPUT = 0x058, PHIDID_PHSENSOR = 0x074, PHIDID_RFID = 0x030, PHIDID_SERVO_1MOTOR = 0x039,
  PHIDID_SERVO_1MOTOR_OLD = 2, PHIDID_SERVO_4MOTOR = 0x038, PHIDID_SERVO_4MOTOR_OLD = 3, PHIDID_TEXTLCD_2x20 = 0x052,
  PHIDID_TEXTLCD_2x20_w_0_8_8 = 0x153, PHIDID_TEXTLED_1x8 = 0x049, PHIDID_TEXTLED_4x8 = 0x048, PHIDID_WEIGHTSENSOR = 0x072,
  PHIDID_FIRMWARE_UPGRADE = 0x098
}
enum  CPhidget_DeviceUID {
  PHIDUID_NOTHING = 1, PHIDUID_ACCELEROMETER_2AXIS_2G, PHIDUID_ACCELEROMETER_2AXIS_10G, PHIDUID_ACCELEROMETER_2AXIS_5G,
  PHIDUID_ACCELEROMETER_3AXIS_3G, PHIDUID_ADVANCEDSERVO_1MOTOR, PHIDUID_ADVANCEDSERVO_8MOTOR, PHIDUID_ADVANCEDSERVO_8MOTOR_PGOOD_FLAG,
  PHIDUID_ADVANCEDSERVO_8MOTOR_CURSENSE_FIX, PHIDUID_ANALOG_4OUTPUT, PHIDUID_BRIDGE_4INPUT, PHIDUID_ENCODER_1ENCODER_1INPUT_OLD,
  PHIDUID_ENCODER_1ENCODER_1INPUT_v1, PHIDUID_ENCODER_1ENCODER_1INPUT_v2, PHIDUID_ENCODER_HS_1ENCODER, PHIDUID_ENCODER_HS_4ENCODER_4INPUT,
  PHIDUID_FREQUENCYCOUNTER_2INPUT, PHIDUID_GPS, PHIDUID_INTERFACEKIT_0_0_4_NO_ECHO, PHIDUID_INTERFACEKIT_0_0_4,
  PHIDUID_INTERFACEKIT_0_0_8, PHIDUID_INTERFACEKIT_0_5_7, PHIDUID_INTERFACEKIT_0_8_8_w_LCD, PHIDUID_INTERFACEKIT_0_16_16_NO_ECHO,
  PHIDUID_INTERFACEKIT_0_16_16_BITBUG, PHIDUID_INTERFACEKIT_0_16_16, PHIDUID_INTERFACEKIT_2_2_2, PHIDUID_INTERFACEKIT_2_8_8,
  PHIDUID_INTERFACEKIT_4_8_8, PHIDUID_INTERFACEKIT_8_8_8_NO_ECHO, PHIDUID_INTERFACEKIT_8_8_8, PHIDUID_INTERFACEKIT_8_8_8_FAST,
  PHIDUID_INTERFACEKIT_8_8_8_w_LCD_NO_ECHO, PHIDUID_INTERFACEKIT_8_8_8_w_LCD, PHIDUID_INTERFACEKIT_8_8_8_w_LCD_FAST, PHIDUID_INTERFACEKIT_TOUCH_SLIDER,
  PHIDUID_INTERFACEKIT_TOUCH_ROTARY, PHIDUID_IR, PHIDUID_LED_64, PHIDUID_LED_64_ADV,
  PHIDUID_MOTORCONTROL_1MOTOR, PHIDUID_MOTORCONTROL_HC_2MOTOR, PHIDUID_MOTORCONTROL_LV_2MOTOR_4INPUT, PHIDUID_PHSENSOR,
  PHIDUID_RFID_OLD, PHIDUID_RFID, PHIDUID_RFID_2OUTPUT_NO_ECHO, PHIDUID_RFID_2OUTPUT,
  PHIDUID_RFID_2OUTPUT_ADVANCED, PHIDUID_SERVO_1MOTOR_OLD, PHIDUID_SERVO_4MOTOR_OLD, PHIDUID_SERVO_1MOTOR_NO_ECHO,
  PHIDUID_SERVO_1MOTOR, PHIDUID_SERVO_4MOTOR_NO_ECHO, PHIDUID_SERVO_4MOTOR, PHIDUID_SPATIAL_ACCEL_3AXIS_1049,
  PHIDUID_SPATIAL_ACCEL_3AXIS_1041, PHIDUID_SPATIAL_ACCEL_3AXIS_1043, PHIDUID_SPATIAL_ACCEL_GYRO_COMPASS_1056, PHIDUID_SPATIAL_ACCEL_GYRO_COMPASS_1056_NEG_GAIN,
  PHIDUID_SPATIAL_ACCEL_GYRO_COMPASS_1042, PHIDUID_SPATIAL_ACCEL_GYRO_COMPASS_1044, PHIDUID_STEPPER_BIPOLAR_1MOTOR, PHIDUID_STEPPER_UNIPOLAR_4MOTOR,
  PHIDUID_TEMPERATURESENSOR_OLD, PHIDUID_TEMPERATURESENSOR, PHIDUID_TEMPERATURESENSOR_AD22100, PHIDUID_TEMPERATURESENSOR_TERMINAL_BLOCKS,
  PHIDUID_TEMPERATURESENSOR_4, PHIDUID_TEMPERATURESENSOR_IR, PHIDUID_TEXTLCD_2x20, PHIDUID_TEXTLCD_2x20_w_8_8_8,
  PHIDUID_TEXTLCD_2x20_w_8_8_8_BRIGHTNESS, PHIDUID_TEXTLCD_ADAPTER, PHIDUID_TEXTLED_1x8, PHIDUID_TEXTLED_4x8,
  PHIDUID_WEIGHTSENSOR, PHIDUID_GENERIC, PHIDUID_FIRMWARE_UPGRADE
}
enum  CPhidget_ServoType {
  PHIDGET_SERVO_DEFAULT = 1, PHIDGET_SERVO_RAW_us_MODE, PHIDGET_SERVO_HITEC_HS322HD, PHIDGET_SERVO_HITEC_HS5245MG,
  PHIDGET_SERVO_HITEC_805BB, PHIDGET_SERVO_HITEC_HS422, PHIDGET_SERVO_TOWERPRO_MG90, PHIDGET_SERVO_HITEC_HSR1425CR,
  PHIDGET_SERVO_HITEC_HS785HB, PHIDGET_SERVO_HITEC_HS485HB, PHIDGET_SERVO_HITEC_HS645MG, PHIDGET_SERVO_HITEC_815BB,
  PHIDGET_SERVO_FIRGELLI_L12_30_50_06_R, PHIDGET_SERVO_FIRGELLI_L12_50_100_06_R, PHIDGET_SERVO_FIRGELLI_L12_50_210_06_R, PHIDGET_SERVO_FIRGELLI_L12_100_50_06_R,
  PHIDGET_SERVO_FIRGELLI_L12_100_100_06_R, PHIDGET_SERVO_SPRINGRC_SM_S2313M, PHIDGET_SERVO_SPRINGRC_SM_S3317M, PHIDGET_SERVO_SPRINGRC_SM_S3317SR,
  PHIDGET_SERVO_SPRINGRC_SM_S4303R, PHIDGET_SERVO_SPRINGRC_SM_S4315M, PHIDGET_SERVO_SPRINGRC_SM_S4315R, PHIDGET_SERVO_SPRINGRC_SM_S4505B,
  PHIDGET_SERVO_USER_DEFINED
}
enum  CPhidgetBridge_Gain {
  PHIDGET_BRIDGE_GAIN_1 = 1, PHIDGET_BRIDGE_GAIN_8, PHIDGET_BRIDGE_GAIN_16, PHIDGET_BRIDGE_GAIN_32,
  PHIDGET_BRIDGE_GAIN_64, PHIDGET_BRIDGE_GAIN_128, PHIDGET_BRIDGE_GAIN_UNKNOWN
}
enum  CPhidgetDictionary_keyChangeReason { PHIDGET_DICTIONARY_VALUE_CHANGED = 1, PHIDGET_DICTIONARY_ENTRY_ADDED, PHIDGET_DICTIONARY_ENTRY_REMOVING, PHIDGET_DICTIONARY_CURRENT_VALUE }
enum  CPhidgetFrequencyCounter_FilterType { PHIDGET_FREQUENCYCOUNTER_FILTERTYPE_ZERO_CROSSING = 1, PHIDGET_FREQUENCYCOUNTER_FILTERTYPE_LOGIC_LEVEL, PHIDGET_FREQUENCYCOUNTER_FILTERTYPE_UNKNOWN }
enum  CPhidgetIR_Encoding {
  PHIDGET_IR_ENCODING_UNKNOWN = 1, PHIDGET_IR_ENCODING_SPACE, PHIDGET_IR_ENCODING_PULSE, PHIDGET_IR_ENCODING_BIPHASE,
  PHIDGET_IR_ENCODING_RC5, PHIDGET_IR_ENCODING_RC6
}
enum  CPhidgetIR_Length { PHIDGET_IR_LENGTH_UNKNOWN = 1, PHIDGET_IR_LENGTH_CONSTANT, PHIDGET_IR_LENGTH_VARIABLE }
enum  CPhidgetLED_CurrentLimit { PHIDGET_LED_CURRENT_LIMIT_20mA = 1, PHIDGET_LED_CURRENT_LIMIT_40mA, PHIDGET_LED_CURRENT_LIMIT_60mA, PHIDGET_LED_CURRENT_LIMIT_80mA }
enum  CPhidgetLED_Voltage { PHIDGET_LED_VOLTAGE_1_7V = 1, PHIDGET_LED_VOLTAGE_2_75V, PHIDGET_LED_VOLTAGE_3_9V, PHIDGET_LED_VOLTAGE_5_0V }
enum  CPhidgetLog_level {
  PHIDGET_LOG_CRITICAL = 1, PHIDGET_LOG_ERROR, PHIDGET_LOG_WARNING, PHIDGET_LOG_DEBUG,
  PHIDGET_LOG_INFO, PHIDGET_LOG_VERBOSE
}
enum  CPhidgetTemperatureSensor_ThermocoupleType { PHIDGET_TEMPERATURE_SENSOR_K_TYPE = 1, PHIDGET_TEMPERATURE_SENSOR_J_TYPE, PHIDGET_TEMPERATURE_SENSOR_E_TYPE, PHIDGET_TEMPERATURE_SENSOR_T_TYPE }
enum  CPhidgetTextLCD_ScreenSize {
  PHIDGET_TEXTLCD_SCREEN_NONE = 1, PHIDGET_TEXTLCD_SCREEN_1x8, PHIDGET_TEXTLCD_SCREEN_2x8, PHIDGET_TEXTLCD_SCREEN_1x16,
  PHIDGET_TEXTLCD_SCREEN_2x16, PHIDGET_TEXTLCD_SCREEN_4x16, PHIDGET_TEXTLCD_SCREEN_2x20, PHIDGET_TEXTLCD_SCREEN_4x20,
  PHIDGET_TEXTLCD_SCREEN_2x24, PHIDGET_TEXTLCD_SCREEN_1x40, PHIDGET_TEXTLCD_SCREEN_2x40, PHIDGET_TEXTLCD_SCREEN_4x40,
  PHIDGET_TEXTLCD_SCREEN_UNKNOWN
}

Functions

int CPhidget_close (CPhidgetHandle phid)
int CPhidget_delete (CPhidgetHandle phid)
int CPhidget_disableLogging ()
int CPhidget_enableLogging (CPhidgetLog_level level, const char *outputFile)
int CPhidget_getDeviceClass (CPhidgetHandle phid, CPhidget_DeviceClass *deviceClass)
int CPhidget_getDeviceID (CPhidgetHandle phid, CPhidget_DeviceID *deviceID)
int CPhidget_getDeviceLabel (CPhidgetHandle phid, const char **deviceLabel)
int CPhidget_getDeviceName (CPhidgetHandle phid, const char **deviceName)
int CPhidget_getDeviceStatus (CPhidgetHandle phid, int *deviceStatus)
int CPhidget_getDeviceType (CPhidgetHandle phid, const char **deviceType)
int CPhidget_getDeviceVersion (CPhidgetHandle phid, int *deviceVersion)
int CPhidget_getErrorDescription (int errorCode, const char **errorString)
int CPhidget_getLibraryVersion (const char **libraryVersion)
int CPhidget_getSerialNumber (CPhidgetHandle phid, int *serialNumber)
int CPhidget_getServerAddress (CPhidgetHandle phid, const char **address, int *port)
int CPhidget_getServerID (CPhidgetHandle phid, const char **serverID)
int CPhidget_getServerStatus (CPhidgetHandle phid, int *serverStatus)
int CPhidget_log (CPhidgetLog_level level, const char *id, const char *message,...)
int CPhidget_open (CPhidgetHandle phid, int serialNumber)
int CPhidget_openLabel (CPhidgetHandle phid, const char *label)
int CPhidget_openLabelRemote (CPhidgetHandle phid, const char *label, const char *serverID, const char *password)
int CPhidget_openLabelRemoteIP (CPhidgetHandle phid, const char *label, const char *address, int port, const char *password)
int CPhidget_openRemote (CPhidgetHandle phid, int serial, const char *serverID, const char *password)
int CPhidget_openRemoteIP (CPhidgetHandle phid, int serial, const char *address, int port, const char *password)
int CPhidget_set_OnAttach_Handler (CPhidgetHandle phid, int(*fptr)(CPhidgetHandle phid, void *userPtr), void *userPtr)
int CPhidget_set_OnDetach_Handler (CPhidgetHandle phid, int(*fptr)(CPhidgetHandle phid, void *userPtr), void *userPtr)
int CPhidget_set_OnError_Handler (CPhidgetHandle phid, int(*fptr)(CPhidgetHandle phid, void *userPtr, int errorCode, const char *errorString), void *userPtr)
int CPhidget_set_OnServerConnect_Handler (CPhidgetHandle phid, int(*fptr)(CPhidgetHandle phid, void *userPtr), void *userPtr)
int CPhidget_set_OnServerDisconnect_Handler (CPhidgetHandle phid, int(*fptr)(CPhidgetHandle phid, void *userPtr), void *userPtr)
int CPhidget_setDeviceLabel (CPhidgetHandle phid, const char *deviceLabel)
int CPhidget_waitForAttachment (CPhidgetHandle phid, int milliseconds)
int CPhidgetAccelerometer_create (CPhidgetAccelerometerHandle *phid)
int CPhidgetAccelerometer_getAcceleration (CPhidgetAccelerometerHandle phid, int index, double *acceleration)
int CPhidgetAccelerometer_getAccelerationChangeTrigger (CPhidgetAccelerometerHandle phid, int index, double *trigger)
int CPhidgetAccelerometer_getAccelerationMax (CPhidgetAccelerometerHandle phid, int index, double *max)
int CPhidgetAccelerometer_getAccelerationMin (CPhidgetAccelerometerHandle phid, int index, double *min)
int CPhidgetAccelerometer_getAxisCount (CPhidgetAccelerometerHandle phid, int *count)
int CPhidgetAccelerometer_set_OnAccelerationChange_Handler (CPhidgetAccelerometerHandle phid, int(*fptr)(CPhidgetAccelerometerHandle phid, void *userPtr, int index, double acceleration), void *userPtr)
int CPhidgetAccelerometer_setAccelerationChangeTrigger (CPhidgetAccelerometerHandle phid, int index, double trigger)
int CPhidgetAdvancedServo_create (CPhidgetAdvancedServoHandle *phid)
int CPhidgetAdvancedServo_getAcceleration (CPhidgetAdvancedServoHandle phid, int index, double *acceleration)
int CPhidgetAdvancedServo_getAccelerationMax (CPhidgetAdvancedServoHandle phid, int index, double *max)
int CPhidgetAdvancedServo_getAccelerationMin (CPhidgetAdvancedServoHandle phid, int index, double *min)
int CPhidgetAdvancedServo_getCurrent (CPhidgetAdvancedServoHandle phid, int index, double *current)
int CPhidgetAdvancedServo_getEngaged (CPhidgetAdvancedServoHandle phid, int index, int *engagedState)
int CPhidgetAdvancedServo_getMotorCount (CPhidgetAdvancedServoHandle phid, int *count)
int CPhidgetAdvancedServo_getPosition (CPhidgetAdvancedServoHandle phid, int index, double *position)
int CPhidgetAdvancedServo_getPositionMax (CPhidgetAdvancedServoHandle phid, int index, double *max)
int CPhidgetAdvancedServo_getPositionMin (CPhidgetAdvancedServoHandle phid, int index, double *min)
int CPhidgetAdvancedServo_getServoType (CPhidgetAdvancedServoHandle phid, int index, CPhidget_ServoType *servoType)
int CPhidgetAdvancedServo_getSpeedRampingOn (CPhidgetAdvancedServoHandle phid, int index, int *rampingState)
int CPhidgetAdvancedServo_getStopped (CPhidgetAdvancedServoHandle phid, int index, int *stoppedState)
int CPhidgetAdvancedServo_getVelocity (CPhidgetAdvancedServoHandle phid, int index, double *velocity)
int CPhidgetAdvancedServo_getVelocityLimit (CPhidgetAdvancedServoHandle phid, int index, double *limit)
int CPhidgetAdvancedServo_getVelocityMax (CPhidgetAdvancedServoHandle phid, int index, double *max)
int CPhidgetAdvancedServo_getVelocityMin (CPhidgetAdvancedServoHandle phid, int index, double *min)
int CPhidgetAdvancedServo_set_OnCurrentChange_Handler (CPhidgetAdvancedServoHandle phid, int(*fptr)(CPhidgetAdvancedServoHandle phid, void *userPtr, int index, double current), void *userPtr)
int CPhidgetAdvancedServo_set_OnPositionChange_Handler (CPhidgetAdvancedServoHandle phid, int(*fptr)(CPhidgetAdvancedServoHandle phid, void *userPtr, int index, double position), void *userPtr)
int CPhidgetAdvancedServo_set_OnVelocityChange_Handler (CPhidgetAdvancedServoHandle phid, int(*fptr)(CPhidgetAdvancedServoHandle phid, void *userPtr, int index, double velocity), void *userPtr)
int CPhidgetAdvancedServo_setAcceleration (CPhidgetAdvancedServoHandle phid, int index, double acceleration)
int CPhidgetAdvancedServo_setEngaged (CPhidgetAdvancedServoHandle phid, int index, int engagedState)
int CPhidgetAdvancedServo_setPosition (CPhidgetAdvancedServoHandle phid, int index, double position)
int CPhidgetAdvancedServo_setPositionMax (CPhidgetAdvancedServoHandle phid, int index, double max)
int CPhidgetAdvancedServo_setPositionMin (CPhidgetAdvancedServoHandle phid, int index, double min)
int CPhidgetAdvancedServo_setServoParameters (CPhidgetAdvancedServoHandle phid, int index, double min_us, double max_us, double degrees, double velocity_max)
int CPhidgetAdvancedServo_setServoType (CPhidgetAdvancedServoHandle phid, int index, CPhidget_ServoType servoType)
int CPhidgetAdvancedServo_setSpeedRampingOn (CPhidgetAdvancedServoHandle phid, int index, int rampingState)
int CPhidgetAdvancedServo_setVelocityLimit (CPhidgetAdvancedServoHandle phid, int index, double limit)
int CPhidgetAnalog_create (CPhidgetAnalogHandle *phid)
int CPhidgetAnalog_getEnabled (CPhidgetAnalogHandle phid, int index, int *enabledState)
int CPhidgetAnalog_getOutputCount (CPhidgetAnalogHandle phid, int *count)
int CPhidgetAnalog_getVoltage (CPhidgetAnalogHandle phid, int index, double *voltage)
int CPhidgetAnalog_getVoltageMax (CPhidgetAnalogHandle phid, int index, double *max)
int CPhidgetAnalog_getVoltageMin (CPhidgetAnalogHandle phid, int index, double *min)
int CPhidgetAnalog_setEnabled (CPhidgetAnalogHandle phid, int index, int enabledState)
int CPhidgetAnalog_setVoltage (CPhidgetAnalogHandle phid, int index, double voltage)
int CPhidgetBridge_create (CPhidgetBridgeHandle *phid)
int CPhidgetBridge_getBridgeMax (CPhidgetBridgeHandle phid, int index, double *max)
int CPhidgetBridge_getBridgeMin (CPhidgetBridgeHandle phid, int index, double *min)
int CPhidgetBridge_getBridgeValue (CPhidgetBridgeHandle phid, int index, double *value)
int CPhidgetBridge_getDataRate (CPhidgetBridgeHandle phid, int *milliseconds)
int CPhidgetBridge_getDataRateMax (CPhidgetBridgeHandle phid, int *max)
int CPhidgetBridge_getDataRateMin (CPhidgetBridgeHandle phid, int *min)
int CPhidgetBridge_getEnabled (CPhidgetBridgeHandle phid, int index, int *enabledState)
int CPhidgetBridge_getGain (CPhidgetBridgeHandle phid, int index, CPhidgetBridge_Gain *gain)
int CPhidgetBridge_getInputCount (CPhidgetBridgeHandle phid, int *count)
int CPhidgetBridge_set_OnBridgeData_Handler (CPhidgetBridgeHandle phid, int(*fptr)(CPhidgetBridgeHandle phid, void *userPtr, int index, double value), void *userPtr)
int CPhidgetBridge_setDataRate (CPhidgetBridgeHandle phid, int milliseconds)
int CPhidgetBridge_setEnabled (CPhidgetBridgeHandle phid, int index, int enabledState)
int CPhidgetBridge_setGain (CPhidgetBridgeHandle phid, int index, CPhidgetBridge_Gain gain)
int CPhidgetDictionary_addKey (CPhidgetDictionaryHandle dict, const char *key, const char *value, int persistent)
int CPhidgetDictionary_close (CPhidgetDictionaryHandle dict)
int CPhidgetDictionary_create (CPhidgetDictionaryHandle *dict)
int CPhidgetDictionary_delete (CPhidgetDictionaryHandle dict)
int CPhidgetDictionary_getKey (CPhidgetDictionaryHandle dict, const char *key, char *value, int valuelen)
int CPhidgetDictionary_getServerAddress (CPhidgetDictionaryHandle dict, const char **address, int *port)
int CPhidgetDictionary_getServerID (CPhidgetDictionaryHandle dict, const char **serverID)
int CPhidgetDictionary_getServerStatus (CPhidgetDictionaryHandle dict, int *serverStatus)
int CPhidgetDictionary_openRemote (CPhidgetDictionaryHandle dict, const char *serverID, const char *password)
int CPhidgetDictionary_openRemoteIP (CPhidgetDictionaryHandle dict, const char *address, int port, const char *password)
int CPhidgetDictionary_remove_OnKeyChange_Handler (CPhidgetDictionaryListenerHandle dictlistener)
int CPhidgetDictionary_removeKey (CPhidgetDictionaryHandle dict, const char *pattern)
int CPhidgetDictionary_set_OnError_Handler (CPhidgetDictionaryHandle dict, int(*fptr)(CPhidgetDictionaryHandle, void *userPtr, int errorCode, const char *errorString), void *userPtr)
int CPhidgetDictionary_set_OnKeyChange_Handler (CPhidgetDictionaryHandle dict, CPhidgetDictionaryListenerHandle *dictlistener, const char *pattern, CPhidgetDictionary_OnKeyChange_Function fptr, void *userPtr)
int CPhidgetDictionary_set_OnServerConnect_Handler (CPhidgetDictionaryHandle dict, int(*fptr)(CPhidgetDictionaryHandle dict, void *userPtr), void *userPtr)
int CPhidgetDictionary_set_OnServerDisconnect_Handler (CPhidgetDictionaryHandle dict, int(*fptr)(CPhidgetDictionaryHandle dict, void *userPtr), void *userPtr)
int CPhidgetEncoder_create (CPhidgetEncoderHandle *phid)
int CPhidgetEncoder_getEnabled (CPhidgetEncoderHandle phid, int index, int *enabledState)
int CPhidgetEncoder_getEncoderCount (CPhidgetEncoderHandle phid, int *count)
int CPhidgetEncoder_getIndexPosition (CPhidgetEncoderHandle phid, int index, int *position)
int CPhidgetEncoder_getInputCount (CPhidgetEncoderHandle phid, int *count)
int CPhidgetEncoder_getInputState (CPhidgetEncoderHandle phid, int index, int *inputState)
int CPhidgetEncoder_getPosition (CPhidgetEncoderHandle phid, int index, int *position)
int CPhidgetEncoder_set_OnIndexChange_Handler (CPhidgetEncoderHandle phid, int(*fptr)(CPhidgetEncoderHandle phid, void *userPtr, int index, int indexPosition), void *userPtr)
int CPhidgetEncoder_set_OnInputChange_Handler (CPhidgetEncoderHandle phid, int(*fptr)(CPhidgetEncoderHandle phid, void *userPtr, int index, int inputState), void *userPtr)
int CPhidgetEncoder_set_OnPositionChange_Handler (CPhidgetEncoderHandle phid, int(*fptr)(CPhidgetEncoderHandle phid, void *userPtr, int index, int time, int positionChange), void *userPtr)
int CPhidgetEncoder_setEnabled (CPhidgetEncoderHandle phid, int index, int enabledState)
int CPhidgetEncoder_setPosition (CPhidgetEncoderHandle phid, int index, int position)
int CPhidgetFrequencyCounter_create (CPhidgetFrequencyCounterHandle *phid)
int CPhidgetFrequencyCounter_getEnabled (CPhidgetFrequencyCounterHandle phid, int index, int *enabledState)
int CPhidgetFrequencyCounter_getFilter (CPhidgetFrequencyCounterHandle phid, int index, CPhidgetFrequencyCounter_FilterType *filter)
int CPhidgetFrequencyCounter_getFrequency (CPhidgetFrequencyCounterHandle phid, int index, double *frequency)
int CPhidgetFrequencyCounter_getFrequencyInputCount (CPhidgetFrequencyCounterHandle phid, int *count)
int CPhidgetFrequencyCounter_getTimeout (CPhidgetFrequencyCounterHandle phid, int index, int *timeout)
int CPhidgetFrequencyCounter_getTotalCount (CPhidgetFrequencyCounterHandle phid, int index, __int64 *count)
int CPhidgetFrequencyCounter_getTotalTime (CPhidgetFrequencyCounterHandle phid, int index, __int64 *time)
int CPhidgetFrequencyCounter_reset (CPhidgetFrequencyCounterHandle phid, int index)
int CPhidgetFrequencyCounter_set_OnCount_Handler (CPhidgetFrequencyCounterHandle phid, int(*fptr)(CPhidgetFrequencyCounterHandle phid, void *userPtr, int index, int time, int counts), void *userPtr)
int CPhidgetFrequencyCounter_setEnabled (CPhidgetFrequencyCounterHandle phid, int index, int enabledState)
int CPhidgetFrequencyCounter_setFilter (CPhidgetFrequencyCounterHandle phid, int index, CPhidgetFrequencyCounter_FilterType filter)
int CPhidgetFrequencyCounter_setTimeout (CPhidgetFrequencyCounterHandle phid, int index, int timeout)
int CPhidgetGPS_create (CPhidgetGPSHandle *phid)
int CPhidgetGPS_getAltitude (CPhidgetGPSHandle phid, double *altitude)
int CPhidgetGPS_getDate (CPhidgetGPSHandle phid, GPSDate *date)
int CPhidgetGPS_getHeading (CPhidgetGPSHandle phid, double *heading)
int CPhidgetGPS_getLatitude (CPhidgetGPSHandle phid, double *latitude)
int CPhidgetGPS_getLongitude (CPhidgetGPSHandle phid, double *longitude)
int CPhidgetGPS_getNMEAData (CPhidgetGPSHandle phid, NMEAData *data)
int CPhidgetGPS_getPositionFixStatus (CPhidgetGPSHandle phid, int *fixStatus)
int CPhidgetGPS_getTime (CPhidgetGPSHandle phid, GPSTime *time)
int CPhidgetGPS_getVelocity (CPhidgetGPSHandle phid, double *velocity)
int CPhidgetGPS_set_OnPositionChange_Handler (CPhidgetGPSHandle phid, int(*fptr)(CPhidgetGPSHandle phid, void *userPtr, double latitude, double longitude, double altitude), void *userPtr)
int CPhidgetGPS_set_OnPositionFixStatusChange_Handler (CPhidgetGPSHandle phid, int(*fptr)(CPhidgetGPSHandle phid, void *userPtr, int status), void *userPtr)
int CPhidgetInterfaceKit_create (CPhidgetInterfaceKitHandle *phid)
int CPhidgetInterfaceKit_getDataRate (CPhidgetInterfaceKitHandle phid, int index, int *milliseconds)
int CPhidgetInterfaceKit_getDataRateMax (CPhidgetInterfaceKitHandle phid, int index, int *max)
int CPhidgetInterfaceKit_getDataRateMin (CPhidgetInterfaceKitHandle phid, int index, int *min)
int CPhidgetInterfaceKit_getInputCount (CPhidgetInterfaceKitHandle phid, int *count)
int CPhidgetInterfaceKit_getInputState (CPhidgetInterfaceKitHandle phid, int index, int *inputState)
int CPhidgetInterfaceKit_getOutputCount (CPhidgetInterfaceKitHandle phid, int *count)
int CPhidgetInterfaceKit_getOutputState (CPhidgetInterfaceKitHandle phid, int index, int *outputState)
int CPhidgetInterfaceKit_getRatiometric (CPhidgetInterfaceKitHandle phid, int *ratiometric)
int CPhidgetInterfaceKit_getSensorChangeTrigger (CPhidgetInterfaceKitHandle phid, int index, int *trigger)
int CPhidgetInterfaceKit_getSensorCount (CPhidgetInterfaceKitHandle phid, int *count)
int CPhidgetInterfaceKit_getSensorRawValue (CPhidgetInterfaceKitHandle phid, int index, int *sensorRawValue)
int CPhidgetInterfaceKit_getSensorValue (CPhidgetInterfaceKitHandle phid, int index, int *sensorValue)
int CPhidgetInterfaceKit_set_OnInputChange_Handler (CPhidgetInterfaceKitHandle phid, int(*fptr)(CPhidgetInterfaceKitHandle phid, void *userPtr, int index, int inputState), void *userPtr)
int CPhidgetInterfaceKit_set_OnOutputChange_Handler (CPhidgetInterfaceKitHandle phid, int(*fptr)(CPhidgetInterfaceKitHandle phid, void *userPtr, int index, int outputState), void *userPtr)
int CPhidgetInterfaceKit_set_OnSensorChange_Handler (CPhidgetInterfaceKitHandle phid, int(*fptr)(CPhidgetInterfaceKitHandle phid, void *userPtr, int index, int sensorValue), void *userPtr)
int CPhidgetInterfaceKit_setDataRate (CPhidgetInterfaceKitHandle phid, int index, int milliseconds)
int CPhidgetInterfaceKit_setOutputState (CPhidgetInterfaceKitHandle phid, int index, int outputState)
int CPhidgetInterfaceKit_setRatiometric (CPhidgetInterfaceKitHandle phid, int ratiometric)
int CPhidgetInterfaceKit_setSensorChangeTrigger (CPhidgetInterfaceKitHandle phid, int index, int trigger)
int CPhidgetIR_create (CPhidgetIRHandle *phid)
int CPhidgetIR_getLastCode (CPhidgetIRHandle phid, unsigned char *data, int *dataLength, int *bitCount)
int CPhidgetIR_getLastLearnedCode (CPhidgetIRHandle phid, unsigned char *data, int *dataLength, CPhidgetIR_CodeInfo *codeInfo)
int CPhidgetIR_getRawData (CPhidgetIRHandle phid, int *data, int *dataLength)
int CPhidgetIR_set_OnCode_Handler (CPhidgetIRHandle phid, int(*fptr)(CPhidgetIRHandle phid, void *userPtr, unsigned char *data, int dataLength, int bitCount, int repeat), void *userPtr)
int CPhidgetIR_set_OnLearn_Handler (CPhidgetIRHandle phid, int(*fptr)(CPhidgetIRHandle phid, void *userPtr, unsigned char *data, int dataLength, CPhidgetIR_CodeInfoHandle codeInfo), void *userPtr)
int CPhidgetIR_set_OnRawData_Handler (CPhidgetIRHandle phid, int(*fptr)(CPhidgetIRHandle phid, void *userPtr, int *data, int dataLength), void *userPtr)
int CPhidgetIR_Transmit (CPhidgetIRHandle phid, unsigned char *data, CPhidgetIR_CodeInfoHandle codeInfo)
int CPhidgetIR_TransmitRaw (CPhidgetIRHandle phid, int *data, int length, int carrierFrequency, int dutyCycle, int gap)
int CPhidgetIR_TransmitRepeat (CPhidgetIRHandle phid)
int CPhidgetLED_create (CPhidgetLEDHandle *phid)
int CPhidgetLED_getCurrentLimit (CPhidgetLEDHandle phid, CPhidgetLED_CurrentLimit *currentLimit)
int CPhidgetLED_getDiscreteLED (CPhidgetLEDHandle phid, int index, int *brightness)
int CPhidgetLED_getLEDCount (CPhidgetLEDHandle phid, int *count)
int CPhidgetLED_getVoltage (CPhidgetLEDHandle phid, CPhidgetLED_Voltage *voltage)
int CPhidgetLED_setCurrentLimit (CPhidgetLEDHandle phid, CPhidgetLED_CurrentLimit currentLimit)
int CPhidgetLED_setDiscreteLED (CPhidgetLEDHandle phid, int index, int brightness)
int CPhidgetLED_setVoltage (CPhidgetLEDHandle phid, CPhidgetLED_Voltage voltage)
int CPhidgetManager_close (CPhidgetManagerHandle phidm)
int CPhidgetManager_create (CPhidgetManagerHandle *phidm)
int CPhidgetManager_delete (CPhidgetManagerHandle phidm)
int CPhidgetManager_freeAttachedDevicesArray (CPhidgetHandle phidArray[])
int CPhidgetManager_getAttachedDevices (CPhidgetManagerHandle phidm, CPhidgetHandle *phidArray[], int *count)
int CPhidgetManager_getServerAddress (CPhidgetManagerHandle phidm, const char **address, int *port)
int CPhidgetManager_getServerID (CPhidgetManagerHandle phidm, const char **serverID)
int CPhidgetManager_getServerStatus (CPhidgetManagerHandle phidm, int *serverStatus)
int CPhidgetManager_open (CPhidgetManagerHandle phidm)
int CPhidgetManager_openRemote (CPhidgetManagerHandle phidm, const char *serverID, const char *password)
int CPhidgetManager_openRemoteIP (CPhidgetManagerHandle phidm, const char *address, int port, const char *password)
int CPhidgetManager_set_OnAttach_Handler (CPhidgetManagerHandle phidm, int(*fptr)(CPhidgetHandle phid, void *userPtr), void *userPtr)
int CPhidgetManager_set_OnDetach_Handler (CPhidgetManagerHandle phidm, int(*fptr)(CPhidgetHandle phid, void *userPtr), void *userPtr)
int CPhidgetManager_set_OnError_Handler (CPhidgetManagerHandle phidm, int(*fptr)(CPhidgetManagerHandle phidm, void *userPtr, int errorCode, const char *errorString), void *userPtr)
int CPhidgetManager_set_OnServerConnect_Handler (CPhidgetManagerHandle phidm, int(*fptr)(CPhidgetManagerHandle phidm, void *userPtr), void *userPtr)
int CPhidgetManager_set_OnServerDisconnect_Handler (CPhidgetManagerHandle phidm, int(*fptr)(CPhidgetManagerHandle phidm, void *userPtr), void *userPtr)
int CPhidgetMotorControl_create (CPhidgetMotorControlHandle *phid)
int CPhidgetMotorControl_getAcceleration (CPhidgetMotorControlHandle phid, int index, double *acceleration)
int CPhidgetMotorControl_getAccelerationMax (CPhidgetMotorControlHandle phid, int index, double *max)
int CPhidgetMotorControl_getAccelerationMin (CPhidgetMotorControlHandle phid, int index, double *min)
int CPhidgetMotorControl_getBackEMF (CPhidgetMotorControlHandle phid, int index, double *voltage)
int CPhidgetMotorControl_getBackEMFSensingState (CPhidgetMotorControlHandle phid, int index, int *bEMFState)
int CPhidgetMotorControl_getBraking (CPhidgetMotorControlHandle phid, int index, double *braking)
int CPhidgetMotorControl_getCurrent (CPhidgetMotorControlHandle phid, int index, double *current)
int CPhidgetMotorControl_getEncoderCount (CPhidgetMotorControlHandle phid, int *count)
int CPhidgetMotorControl_getEncoderPosition (CPhidgetMotorControlHandle phid, int index, int *position)
int CPhidgetMotorControl_getInputCount (CPhidgetMotorControlHandle phid, int *count)
int CPhidgetMotorControl_getInputState (CPhidgetMotorControlHandle phid, int index, int *inputState)
int CPhidgetMotorControl_getMotorCount (CPhidgetMotorControlHandle phid, int *count)
int CPhidgetMotorControl_getRatiometric (CPhidgetMotorControlHandle phid, int *ratiometric)
int CPhidgetMotorControl_getSensorCount (CPhidgetMotorControlHandle phid, int *count)
int CPhidgetMotorControl_getSensorRawValue (CPhidgetMotorControlHandle phid, int index, int *sensorRawValue)
int CPhidgetMotorControl_getSensorValue (CPhidgetMotorControlHandle phid, int index, int *sensorValue)
int CPhidgetMotorControl_getSupplyVoltage (CPhidgetMotorControlHandle phid, double *supplyVoltage)
int CPhidgetMotorControl_getVelocity (CPhidgetMotorControlHandle phid, int index, double *velocity)
int CPhidgetMotorControl_set_OnBackEMFUpdate_Handler (CPhidgetMotorControlHandle phid, int(*fptr)(CPhidgetMotorControlHandle phid, void *userPtr, int index, double voltage), void *userPtr)
int CPhidgetMotorControl_set_OnCurrentChange_Handler (CPhidgetMotorControlHandle phid, int(*fptr)(CPhidgetMotorControlHandle phid, void *userPtr, int index, double current), void *userPtr)
int CPhidgetMotorControl_set_OnCurrentUpdate_Handler (CPhidgetMotorControlHandle phid, int(*fptr)(CPhidgetMotorControlHandle phid, void *userPtr, int index, double current), void *userPtr)
int CPhidgetMotorControl_set_OnEncoderPositionChange_Handler (CPhidgetMotorControlHandle phid, int(*fptr)(CPhidgetMotorControlHandle phid, void *userPtr, int index, int time, int positionChange), void *userPtr)
int CPhidgetMotorControl_set_OnEncoderPositionUpdate_Handler (CPhidgetMotorControlHandle phid, int(*fptr)(CPhidgetMotorControlHandle phid, void *userPtr, int index, int positionChange), void *userPtr)
int CPhidgetMotorControl_set_OnInputChange_Handler (CPhidgetMotorControlHandle phid, int(*fptr)(CPhidgetMotorControlHandle phid, void *userPtr, int index, int inputState), void *userPtr)
int CPhidgetMotorControl_set_OnSensorUpdate_Handler (CPhidgetMotorControlHandle phid, int(*fptr)(CPhidgetMotorControlHandle phid, void *userPtr, int index, int sensorValue), void *userPtr)
int CPhidgetMotorControl_set_OnVelocityChange_Handler (CPhidgetMotorControlHandle phid, int(*fptr)(CPhidgetMotorControlHandle phid, void *userPtr, int index, double velocity), void *userPtr)
int CPhidgetMotorControl_setAcceleration (CPhidgetMotorControlHandle phid, int index, double acceleration)
int CPhidgetMotorControl_setBackEMFSensingState (CPhidgetMotorControlHandle phid, int index, int bEMFState)
int CPhidgetMotorControl_setBraking (CPhidgetMotorControlHandle phid, int index, double braking)
int CPhidgetMotorControl_setEncoderPosition (CPhidgetMotorControlHandle phid, int index, int position)
int CPhidgetMotorControl_setRatiometric (CPhidgetMotorControlHandle phid, int ratiometric)
int CPhidgetMotorControl_setVelocity (CPhidgetMotorControlHandle phid, int index, double velocity)
int CPhidgetPHSensor_create (CPhidgetPHSensorHandle *phid)
int CPhidgetPHSensor_getPH (CPhidgetPHSensorHandle phid, double *ph)
int CPhidgetPHSensor_getPHChangeTrigger (CPhidgetPHSensorHandle phid, double *trigger)
int CPhidgetPHSensor_getPHMax (CPhidgetPHSensorHandle phid, double *max)
int CPhidgetPHSensor_getPHMin (CPhidgetPHSensorHandle phid, double *min)
int CPhidgetPHSensor_getPotential (CPhidgetPHSensorHandle phid, double *potential)
int CPhidgetPHSensor_getPotentialMax (CPhidgetPHSensorHandle phid, double *max)
int CPhidgetPHSensor_getPotentialMin (CPhidgetPHSensorHandle phid, double *min)
int CPhidgetPHSensor_set_OnPHChange_Handler (CPhidgetPHSensorHandle phid, int(*fptr)(CPhidgetPHSensorHandle phid, void *userPtr, double ph), void *userPtr)
int CPhidgetPHSensor_setPHChangeTrigger (CPhidgetPHSensorHandle phid, double trigger)
int CPhidgetPHSensor_setTemperature (CPhidgetPHSensorHandle phid, double temperature)
int CPhidgetRFID_create (CPhidgetRFIDHandle *phid)
int CPhidgetRFID_getAntennaOn (CPhidgetRFIDHandle phid, int *antennaState)
int CPhidgetRFID_getLastTag (CPhidgetRFIDHandle phid, unsigned char *tag)
int CPhidgetRFID_getLEDOn (CPhidgetRFIDHandle phid, int *LEDState)
int CPhidgetRFID_getOutputCount (CPhidgetRFIDHandle phid, int *count)
int CPhidgetRFID_getOutputState (CPhidgetRFIDHandle phid, int index, int *outputState)
int CPhidgetRFID_getTagStatus (CPhidgetRFIDHandle phid, int *status)
int CPhidgetRFID_set_OnOutputChange_Handler (CPhidgetRFIDHandle phid, int(*fptr)(CPhidgetRFIDHandle phid, void *userPtr, int index, int outputState), void *userPtr)
int CPhidgetRFID_set_OnTag_Handler (CPhidgetRFIDHandle phid, int(*fptr)(CPhidgetRFIDHandle phid, void *userPtr, unsigned char *tag), void *userPtr)
int CPhidgetRFID_set_OnTagLost_Handler (CPhidgetRFIDHandle phid, int(*fptr)(CPhidgetRFIDHandle phid, void *userPtr, unsigned char *tag), void *userPtr)
int CPhidgetRFID_setAntennaOn (CPhidgetRFIDHandle phid, int antennaState)
int CPhidgetRFID_setLEDOn (CPhidgetRFIDHandle phid, int LEDState)
int CPhidgetRFID_setOutputState (CPhidgetRFIDHandle phid, int index, int outputState)
int CPhidgetServo_create (CPhidgetServoHandle *phid)
int CPhidgetServo_getEngaged (CPhidgetServoHandle phid, int index, int *engagedState)
int CPhidgetServo_getMotorCount (CPhidgetServoHandle phid, int *count)
int CPhidgetServo_getPosition (CPhidgetServoHandle phid, int index, double *position)
int CPhidgetServo_getPositionMax (CPhidgetServoHandle phid, int index, double *max)
int CPhidgetServo_getPositionMin (CPhidgetServoHandle phid, int index, double *min)
int CPhidgetServo_getServoType (CPhidgetServoHandle phid, int index, CPhidget_ServoType *servoType)
int CPhidgetServo_set_OnPositionChange_Handler (CPhidgetServoHandle phid, int(*fptr)(CPhidgetServoHandle phid, void *userPtr, int index, double position), void *userPtr)
int CPhidgetServo_setEngaged (CPhidgetServoHandle phid, int index, int engagedState)
int CPhidgetServo_setPosition (CPhidgetServoHandle phid, int index, double position)
int CPhidgetServo_setServoParameters (CPhidgetServoHandle phid, int index, double min_us, double max_us, double degrees)
int CPhidgetServo_setServoType (CPhidgetServoHandle phid, int index, CPhidget_ServoType servoType)
int CPhidgetSpatial_create (CPhidgetSpatialHandle *phid)
int CPhidgetSpatial_getAcceleration (CPhidgetSpatialHandle phid, int index, double *acceleration)
int CPhidgetSpatial_getAccelerationAxisCount (CPhidgetSpatialHandle phid, int *count)
int CPhidgetSpatial_getAccelerationMax (CPhidgetSpatialHandle phid, int index, double *max)
int CPhidgetSpatial_getAccelerationMin (CPhidgetSpatialHandle phid, int index, double *min)
int CPhidgetSpatial_getAngularRate (CPhidgetSpatialHandle phid, int index, double *angularRate)
int CPhidgetSpatial_getAngularRateMax (CPhidgetSpatialHandle phid, int index, double *max)
int CPhidgetSpatial_getAngularRateMin (CPhidgetSpatialHandle phid, int index, double *min)
int CPhidgetSpatial_getCompassAxisCount (CPhidgetSpatialHandle phid, int *count)
int CPhidgetSpatial_getDataRate (CPhidgetSpatialHandle phid, int *milliseconds)
int CPhidgetSpatial_getDataRateMax (CPhidgetSpatialHandle phid, int *max)
int CPhidgetSpatial_getDataRateMin (CPhidgetSpatialHandle phid, int *min)
int CPhidgetSpatial_getGyroAxisCount (CPhidgetSpatialHandle phid, int *count)
int CPhidgetSpatial_getMagneticField (CPhidgetSpatialHandle phid, int index, double *magneticField)
int CPhidgetSpatial_getMagneticFieldMax (CPhidgetSpatialHandle phid, int index, double *max)
int CPhidgetSpatial_getMagneticFieldMin (CPhidgetSpatialHandle phid, int index, double *min)
int CPhidgetSpatial_resetCompassCorrectionParameters (CPhidgetSpatialHandle phid)
int CPhidgetSpatial_set_OnSpatialData_Handler (CPhidgetSpatialHandle phid, int(*fptr)(CPhidgetSpatialHandle phid, void *userPtr, CPhidgetSpatial_SpatialEventDataHandle *data, int dataCount), void *userPtr)
int CPhidgetSpatial_setCompassCorrectionParameters (CPhidgetSpatialHandle phid, double magField, double offset0, double offset1, double offset2, double gain0, double gain1, double gain2, double T0, double T1, double T2, double T3, double T4, double T5)
int CPhidgetSpatial_setDataRate (CPhidgetSpatialHandle phid, int milliseconds)
int CPhidgetSpatial_zeroGyro (CPhidgetSpatialHandle phid)
int CPhidgetStepper_create (CPhidgetStepperHandle *phid)
int CPhidgetStepper_getAcceleration (CPhidgetStepperHandle phid, int index, double *acceleration)
int CPhidgetStepper_getAccelerationMax (CPhidgetStepperHandle phid, int index, double *max)
int CPhidgetStepper_getAccelerationMin (CPhidgetStepperHandle phid, int index, double *min)
int CPhidgetStepper_getCurrent (CPhidgetStepperHandle phid, int index, double *current)
int CPhidgetStepper_getCurrentLimit (CPhidgetStepperHandle phid, int index, double *limit)
int CPhidgetStepper_getCurrentMax (CPhidgetStepperHandle phid, int index, double *max)
int CPhidgetStepper_getCurrentMin (CPhidgetStepperHandle phid, int index, double *min)
int CPhidgetStepper_getCurrentPosition (CPhidgetStepperHandle phid, int index, __int64 *position)
int CPhidgetStepper_getEngaged (CPhidgetStepperHandle phid, int index, int *engagedState)
int CPhidgetStepper_getInputCount (CPhidgetStepperHandle phid, int *count)
int CPhidgetStepper_getInputState (CPhidgetStepperHandle phid, int index, int *inputState)
int CPhidgetStepper_getMotorCount (CPhidgetStepperHandle phid, int *count)
int CPhidgetStepper_getPositionMax (CPhidgetStepperHandle phid, int index, __int64 *max)
int CPhidgetStepper_getPositionMin (CPhidgetStepperHandle phid, int index, __int64 *min)
int CPhidgetStepper_getStopped (CPhidgetStepperHandle phid, int index, int *stoppedState)
int CPhidgetStepper_getTargetPosition (CPhidgetStepperHandle phid, int index, __int64 *position)
int CPhidgetStepper_getVelocity (CPhidgetStepperHandle phid, int index, double *velocity)
int CPhidgetStepper_getVelocityLimit (CPhidgetStepperHandle phid, int index, double *limit)
int CPhidgetStepper_getVelocityMax (CPhidgetStepperHandle phid, int index, double *max)
int CPhidgetStepper_getVelocityMin (CPhidgetStepperHandle phid, int index, double *min)
int CPhidgetStepper_set_OnCurrentChange_Handler (CPhidgetStepperHandle phid, int(*fptr)(CPhidgetStepperHandle phid, void *userPtr, int index, double current), void *userPtr)
int CPhidgetStepper_set_OnInputChange_Handler (CPhidgetStepperHandle phid, int(*fptr)(CPhidgetStepperHandle phid, void *userPtr, int index, int inputState), void *userPtr)
int CPhidgetStepper_set_OnPositionChange_Handler (CPhidgetStepperHandle phid, int(*fptr)(CPhidgetStepperHandle phid, void *userPtr, int index, __int64 position), void *userPtr)
int CPhidgetStepper_set_OnVelocityChange_Handler (CPhidgetStepperHandle phid, int(*fptr)(CPhidgetStepperHandle phid, void *userPtr, int index, double velocity), void *userPtr)
int CPhidgetStepper_setAcceleration (CPhidgetStepperHandle phid, int index, double acceleration)
int CPhidgetStepper_setCurrentLimit (CPhidgetStepperHandle phid, int index, double limit)
int CPhidgetStepper_setCurrentPosition (CPhidgetStepperHandle phid, int index, __int64 position)
int CPhidgetStepper_setEngaged (CPhidgetStepperHandle phid, int index, int engagedState)
int CPhidgetStepper_setTargetPosition (CPhidgetStepperHandle phid, int index, __int64 position)
int CPhidgetStepper_setVelocityLimit (CPhidgetStepperHandle phid, int index, double limit)
int CPhidgetTemperatureSensor_create (CPhidgetTemperatureSensorHandle *phid)
int CPhidgetTemperatureSensor_getAmbientTemperature (CPhidgetTemperatureSensorHandle phid, double *ambient)
int CPhidgetTemperatureSensor_getAmbientTemperatureMax (CPhidgetTemperatureSensorHandle phid, double *max)
int CPhidgetTemperatureSensor_getAmbientTemperatureMin (CPhidgetTemperatureSensorHandle phid, double *min)
int CPhidgetTemperatureSensor_getPotential (CPhidgetTemperatureSensorHandle phid, int index, double *potential)
int CPhidgetTemperatureSensor_getPotentialMax (CPhidgetTemperatureSensorHandle phid, int index, double *max)
int CPhidgetTemperatureSensor_getPotentialMin (CPhidgetTemperatureSensorHandle phid, int index, double *min)
int CPhidgetTemperatureSensor_getTemperature (CPhidgetTemperatureSensorHandle phid, int index, double *temperature)
int CPhidgetTemperatureSensor_getTemperatureChangeTrigger (CPhidgetTemperatureSensorHandle phid, int index, double *trigger)
int CPhidgetTemperatureSensor_getTemperatureInputCount (CPhidgetTemperatureSensorHandle phid, int *count)
int CPhidgetTemperatureSensor_getTemperatureMax (CPhidgetTemperatureSensorHandle phid, int index, double *max)
int CPhidgetTemperatureSensor_getTemperatureMin (CPhidgetTemperatureSensorHandle phid, int index, double *min)
int CPhidgetTemperatureSensor_getThermocoupleType (CPhidgetTemperatureSensorHandle phid, int index, CPhidgetTemperatureSensor_ThermocoupleType *type)
int CPhidgetTemperatureSensor_set_OnTemperatureChange_Handler (CPhidgetTemperatureSensorHandle phid, int(*fptr)(CPhidgetTemperatureSensorHandle phid, void *userPtr, int index, double temperature), void *userPtr)
int CPhidgetTemperatureSensor_setTemperatureChangeTrigger (CPhidgetTemperatureSensorHandle phid, int index, double trigger)
int CPhidgetTemperatureSensor_setThermocoupleType (CPhidgetTemperatureSensorHandle phid, int index, CPhidgetTemperatureSensor_ThermocoupleType type)
int CPhidgetTextLCD_create (CPhidgetTextLCDHandle *phid)
int CPhidgetTextLCD_getBacklight (CPhidgetTextLCDHandle phid, int *backlightState)
int CPhidgetTextLCD_getBrightness (CPhidgetTextLCDHandle phid, int *brightness)
int CPhidgetTextLCD_getColumnCount (CPhidgetTextLCDHandle phid, int *count)
int CPhidgetTextLCD_getContrast (CPhidgetTextLCDHandle phid, int *contrast)
int CPhidgetTextLCD_getCursorBlink (CPhidgetTextLCDHandle phid, int *cursorBlinkState)
int CPhidgetTextLCD_getCursorOn (CPhidgetTextLCDHandle phid, int *cursorState)
int CPhidgetTextLCD_getRowCount (CPhidgetTextLCDHandle phid, int *count)
int CPhidgetTextLCD_getScreen (CPhidgetTextLCDHandle phid, int *screenIndex)
int CPhidgetTextLCD_getScreenCount (CPhidgetTextLCDHandle phid, int *count)
int CPhidgetTextLCD_getScreenSize (CPhidgetTextLCDHandle phid, CPhidgetTextLCD_ScreenSize *screenSize)
int CPhidgetTextLCD_initialize (CPhidgetTextLCDHandle phid)
int CPhidgetTextLCD_setBacklight (CPhidgetTextLCDHandle phid, int backlightState)
int CPhidgetTextLCD_setBrightness (CPhidgetTextLCDHandle phid, int brightness)
int CPhidgetTextLCD_setContrast (CPhidgetTextLCDHandle phid, int contrast)
int CPhidgetTextLCD_setCursorBlink (CPhidgetTextLCDHandle phid, int cursorBlinkState)
int CPhidgetTextLCD_setCursorOn (CPhidgetTextLCDHandle phid, int cursorState)
int CPhidgetTextLCD_setCustomCharacter (CPhidgetTextLCDHandle phid, int index, int var1, int var2)
int CPhidgetTextLCD_setDisplayCharacter (CPhidgetTextLCDHandle phid, int index, int column, unsigned char character)
int CPhidgetTextLCD_setDisplayString (CPhidgetTextLCDHandle phid, int index, char *displayString)
int CPhidgetTextLCD_setScreen (CPhidgetTextLCDHandle phid, int screenIndex)
int CPhidgetTextLCD_setScreenSize (CPhidgetTextLCDHandle phid, CPhidgetTextLCD_ScreenSize screenSize)
int CPhidgetTextLED_create (CPhidgetTextLEDHandle *phid)
int CPhidgetTextLED_getBrightness (CPhidgetTextLEDHandle phid, int *brightness)
int CPhidgetTextLED_getColumnCount (CPhidgetTextLEDHandle phid, int *count)
int CPhidgetTextLED_getRowCount (CPhidgetTextLEDHandle phid, int *count)
int CPhidgetTextLED_setBrightness (CPhidgetTextLEDHandle phid, int brightness)
int CPhidgetTextLED_setDisplayString (CPhidgetTextLEDHandle phid, int index, char *displayString)
int CPhidgetWeightSensor_create (CPhidgetWeightSensorHandle *phid)
int CPhidgetWeightSensor_getWeight (CPhidgetWeightSensorHandle phid, double *weight)
int CPhidgetWeightSensor_getWeightChangeTrigger (CPhidgetWeightSensorHandle phid, double *trigger)
int CPhidgetWeightSensor_set_OnWeightChange_Handler (CPhidgetWeightSensorHandle phid, int(*fptr)(CPhidgetWeightSensorHandle phid, void *userPtr, double weight), void *userPtr)
int CPhidgetWeightSensor_setWeightChangeTrigger (CPhidgetWeightSensorHandle phid, double trigger)

Define Documentation

#define CCONV

Definition at line 11 of file phidget21.h.

Definition at line 773 of file phidget21.h.


Typedef Documentation

typedef long long __int64

Definition at line 17 of file phidget21.h.

typedef struct _CPhidgetAccelerometer* CPhidgetAccelerometerHandle

Definition at line 265 of file phidget21.h.

typedef struct _CPhidgetAdvancedServo* CPhidgetAdvancedServoHandle

Definition at line 274 of file phidget21.h.

typedef struct _CPhidgetAnalog* CPhidgetAnalogHandle

Definition at line 331 of file phidget21.h.

typedef struct _CPhidgetBridge* CPhidgetBridgeHandle

Definition at line 349 of file phidget21.h.

typedef int( * CPhidgetDictionary_OnKeyChange_Function)(CPhidgetDictionaryHandle dict, void *userPtr, const char *key, const char *value, CPhidgetDictionary_keyChangeReason reason)

Definition at line 220 of file phidget21.h.

typedef struct _CPhidgetDictionary* CPhidgetDictionaryHandle

Definition at line 211 of file phidget21.h.

typedef struct _CPhidgetDictionaryListener* CPhidgetDictionaryListenerHandle

Definition at line 212 of file phidget21.h.

typedef struct _CPhidgetEncoder* CPhidgetEncoderHandle

Definition at line 364 of file phidget21.h.

typedef struct _CPhidgetFrequencyCounter* CPhidgetFrequencyCounterHandle

Definition at line 382 of file phidget21.h.

typedef struct _CPhidgetGPS* CPhidgetGPSHandle

Definition at line 469 of file phidget21.h.

typedef struct _CPhidget* CPhidgetHandle

Definition at line 22 of file phidget21.h.

typedef struct _CPhidgetInterfaceKit* CPhidgetInterfaceKitHandle

Definition at line 482 of file phidget21.h.

typedef struct _CPhidgetIR* CPhidgetIRHandle

Definition at line 503 of file phidget21.h.

typedef struct _CPhidgetLED* CPhidgetLEDHandle

Definition at line 543 of file phidget21.h.

typedef struct _CPhidgetManager* CPhidgetManagerHandle

Definition at line 231 of file phidget21.h.

typedef struct _CPhidgetMotorControl* CPhidgetMotorControlHandle

Definition at line 564 of file phidget21.h.

typedef struct _CPhidgetPHSensor* CPhidgetPHSensorHandle

Definition at line 598 of file phidget21.h.

typedef struct _CPhidgetRFID* CPhidgetRFIDHandle

Definition at line 610 of file phidget21.h.

typedef struct _CPhidgetServo* CPhidgetServoHandle

Definition at line 624 of file phidget21.h.

typedef struct _CPhidgetSpatial* CPhidgetSpatialHandle

Definition at line 637 of file phidget21.h.

typedef struct _CPhidgetStepper* CPhidgetStepperHandle

Definition at line 666 of file phidget21.h.

typedef struct _CPhidgetTemperatureSensor* CPhidgetTemperatureSensorHandle

Definition at line 698 of file phidget21.h.

typedef struct _CPhidgetTextLCD* CPhidgetTextLCDHandle

Definition at line 721 of file phidget21.h.

typedef struct _CPhidgetTextLED* CPhidgetTextLEDHandle

Definition at line 759 of file phidget21.h.

typedef struct _CPhidgetWeightSensor* CPhidgetWeightSensorHandle

Definition at line 766 of file phidget21.h.


Enumeration Type Documentation

Enumerator:
PHIDCLASS_ACCELEROMETER 
PHIDCLASS_ADVANCEDSERVO 
PHIDCLASS_ANALOG 
PHIDCLASS_BRIDGE 
PHIDCLASS_ENCODER 
PHIDCLASS_FREQUENCYCOUNTER 
PHIDCLASS_GPS 
PHIDCLASS_INTERFACEKIT 
PHIDCLASS_IR 
PHIDCLASS_LED 
PHIDCLASS_MOTORCONTROL 
PHIDCLASS_PHSENSOR 
PHIDCLASS_RFID 
PHIDCLASS_SERVO 
PHIDCLASS_SPATIAL 
PHIDCLASS_STEPPER 
PHIDCLASS_TEMPERATURESENSOR 
PHIDCLASS_TEXTLCD 
PHIDCLASS_TEXTLED 
PHIDCLASS_WEIGHTSENSOR 

Definition at line 27 of file phidget21.h.

Enumerator:
PHIDID_ACCELEROMETER_3AXIS 
PHIDID_ADVANCEDSERVO_1MOTOR 
PHIDID_ADVANCEDSERVO_8MOTOR 
PHIDID_ANALOG_4OUTPUT 
PHIDID_BIPOLAR_STEPPER_1MOTOR 
PHIDID_BRIDGE_4INPUT 
PHIDID_ENCODER_1ENCODER_1INPUT 
PHIDID_ENCODER_HS_1ENCODER 
PHIDID_ENCODER_HS_4ENCODER_4INPUT 
PHIDID_FREQUENCYCOUNTER_2INPUT 
PHIDID_GPS 
PHIDID_INTERFACEKIT_0_0_4 
PHIDID_INTERFACEKIT_0_0_8 
PHIDID_INTERFACEKIT_0_16_16 
PHIDID_INTERFACEKIT_2_2_2 
PHIDID_INTERFACEKIT_8_8_8 
PHIDID_INTERFACEKIT_8_8_8_w_LCD 
PHIDID_IR 
PHIDID_LED_64_ADV 
PHIDID_LINEAR_TOUCH 
PHIDID_MOTORCONTROL_1MOTOR 
PHIDID_MOTORCONTROL_HC_2MOTOR 
PHIDID_RFID_2OUTPUT 
PHIDID_ROTARY_TOUCH 
PHIDID_SPATIAL_ACCEL_3AXIS 
PHIDID_SPATIAL_ACCEL_GYRO_COMPASS 
PHIDID_TEMPERATURESENSOR 
PHIDID_TEMPERATURESENSOR_4 
PHIDID_TEMPERATURESENSOR_IR 
PHIDID_TEXTLCD_2x20_w_8_8_8 
PHIDID_TEXTLCD_ADAPTER 
PHIDID_UNIPOLAR_STEPPER_4MOTOR 
PHIDID_ACCELEROMETER_2AXIS 
PHIDID_INTERFACEKIT_0_8_8_w_LCD 
PHIDID_INTERFACEKIT_4_8_8 
PHIDID_LED_64 
PHIDID_MOTORCONTROL_LV_2MOTOR_4INPUT 
PHIDID_PHSENSOR 
PHIDID_RFID 
PHIDID_SERVO_1MOTOR 
PHIDID_SERVO_1MOTOR_OLD 
PHIDID_SERVO_4MOTOR 
PHIDID_SERVO_4MOTOR_OLD 
PHIDID_TEXTLCD_2x20 
PHIDID_TEXTLCD_2x20_w_0_8_8 
PHIDID_TEXTLED_1x8 
PHIDID_TEXTLED_4x8 
PHIDID_WEIGHTSENSOR 
PHIDID_FIRMWARE_UPGRADE 

Definition at line 49 of file phidget21.h.

Enumerator:
PHIDUID_NOTHING 
PHIDUID_ACCELEROMETER_2AXIS_2G 
PHIDUID_ACCELEROMETER_2AXIS_10G 
PHIDUID_ACCELEROMETER_2AXIS_5G 
PHIDUID_ACCELEROMETER_3AXIS_3G 
PHIDUID_ADVANCEDSERVO_1MOTOR 
PHIDUID_ADVANCEDSERVO_8MOTOR 
PHIDUID_ADVANCEDSERVO_8MOTOR_PGOOD_FLAG 
PHIDUID_ADVANCEDSERVO_8MOTOR_CURSENSE_FIX 
PHIDUID_ANALOG_4OUTPUT 
PHIDUID_BRIDGE_4INPUT 
PHIDUID_ENCODER_1ENCODER_1INPUT_OLD 
PHIDUID_ENCODER_1ENCODER_1INPUT_v1 
PHIDUID_ENCODER_1ENCODER_1INPUT_v2 
PHIDUID_ENCODER_HS_1ENCODER 
PHIDUID_ENCODER_HS_4ENCODER_4INPUT 
PHIDUID_FREQUENCYCOUNTER_2INPUT 
PHIDUID_GPS 
PHIDUID_INTERFACEKIT_0_0_4_NO_ECHO 
PHIDUID_INTERFACEKIT_0_0_4 
PHIDUID_INTERFACEKIT_0_0_8 
PHIDUID_INTERFACEKIT_0_5_7 
PHIDUID_INTERFACEKIT_0_8_8_w_LCD 
PHIDUID_INTERFACEKIT_0_16_16_NO_ECHO 
PHIDUID_INTERFACEKIT_0_16_16_BITBUG 
PHIDUID_INTERFACEKIT_0_16_16 
PHIDUID_INTERFACEKIT_2_2_2 
PHIDUID_INTERFACEKIT_2_8_8 
PHIDUID_INTERFACEKIT_4_8_8 
PHIDUID_INTERFACEKIT_8_8_8_NO_ECHO 
PHIDUID_INTERFACEKIT_8_8_8 
PHIDUID_INTERFACEKIT_8_8_8_FAST 
PHIDUID_INTERFACEKIT_8_8_8_w_LCD_NO_ECHO 
PHIDUID_INTERFACEKIT_8_8_8_w_LCD 
PHIDUID_INTERFACEKIT_8_8_8_w_LCD_FAST 
PHIDUID_INTERFACEKIT_TOUCH_SLIDER 
PHIDUID_INTERFACEKIT_TOUCH_ROTARY 
PHIDUID_IR 
PHIDUID_LED_64 
PHIDUID_LED_64_ADV 
PHIDUID_MOTORCONTROL_1MOTOR 
PHIDUID_MOTORCONTROL_HC_2MOTOR 
PHIDUID_MOTORCONTROL_LV_2MOTOR_4INPUT 
PHIDUID_PHSENSOR 
PHIDUID_RFID_OLD 
PHIDUID_RFID 
PHIDUID_RFID_2OUTPUT_NO_ECHO 
PHIDUID_RFID_2OUTPUT 
PHIDUID_RFID_2OUTPUT_ADVANCED 
PHIDUID_SERVO_1MOTOR_OLD 
PHIDUID_SERVO_4MOTOR_OLD 
PHIDUID_SERVO_1MOTOR_NO_ECHO 
PHIDUID_SERVO_1MOTOR 
PHIDUID_SERVO_4MOTOR_NO_ECHO 
PHIDUID_SERVO_4MOTOR 
PHIDUID_SPATIAL_ACCEL_3AXIS_1049 
PHIDUID_SPATIAL_ACCEL_3AXIS_1041 
PHIDUID_SPATIAL_ACCEL_3AXIS_1043 
PHIDUID_SPATIAL_ACCEL_GYRO_COMPASS_1056 
PHIDUID_SPATIAL_ACCEL_GYRO_COMPASS_1056_NEG_GAIN 
PHIDUID_SPATIAL_ACCEL_GYRO_COMPASS_1042 
PHIDUID_SPATIAL_ACCEL_GYRO_COMPASS_1044 
PHIDUID_STEPPER_BIPOLAR_1MOTOR 
PHIDUID_STEPPER_UNIPOLAR_4MOTOR 
PHIDUID_TEMPERATURESENSOR_OLD 
PHIDUID_TEMPERATURESENSOR 
PHIDUID_TEMPERATURESENSOR_AD22100 
PHIDUID_TEMPERATURESENSOR_TERMINAL_BLOCKS 
PHIDUID_TEMPERATURESENSOR_4 
PHIDUID_TEMPERATURESENSOR_IR 
PHIDUID_TEXTLCD_2x20 
PHIDUID_TEXTLCD_2x20_w_8_8_8 
PHIDUID_TEXTLCD_2x20_w_8_8_8_BRIGHTNESS 
PHIDUID_TEXTLCD_ADAPTER 
PHIDUID_TEXTLED_1x8 
PHIDUID_TEXTLED_4x8 
PHIDUID_WEIGHTSENSOR 
PHIDUID_GENERIC 
PHIDUID_FIRMWARE_UPGRADE 

Definition at line 100 of file phidget21.h.

Enumerator:
PHIDGET_SERVO_DEFAULT 
PHIDGET_SERVO_RAW_us_MODE 
PHIDGET_SERVO_HITEC_HS322HD 
PHIDGET_SERVO_HITEC_HS5245MG 
PHIDGET_SERVO_HITEC_805BB 
PHIDGET_SERVO_HITEC_HS422 
PHIDGET_SERVO_TOWERPRO_MG90 
PHIDGET_SERVO_HITEC_HSR1425CR 
PHIDGET_SERVO_HITEC_HS785HB 
PHIDGET_SERVO_HITEC_HS485HB 
PHIDGET_SERVO_HITEC_HS645MG 
PHIDGET_SERVO_HITEC_815BB 
PHIDGET_SERVO_FIRGELLI_L12_30_50_06_R 
PHIDGET_SERVO_FIRGELLI_L12_50_100_06_R 
PHIDGET_SERVO_FIRGELLI_L12_50_210_06_R 
PHIDGET_SERVO_FIRGELLI_L12_100_50_06_R 
PHIDGET_SERVO_FIRGELLI_L12_100_100_06_R 
PHIDGET_SERVO_SPRINGRC_SM_S2313M 
PHIDGET_SERVO_SPRINGRC_SM_S3317M 
PHIDGET_SERVO_SPRINGRC_SM_S3317SR 
PHIDGET_SERVO_SPRINGRC_SM_S4303R 
PHIDGET_SERVO_SPRINGRC_SM_S4315M 
PHIDGET_SERVO_SPRINGRC_SM_S4315R 
PHIDGET_SERVO_SPRINGRC_SM_S4505B 
PHIDGET_SERVO_USER_DEFINED 

Definition at line 276 of file phidget21.h.

Enumerator:
PHIDGET_BRIDGE_GAIN_1 
PHIDGET_BRIDGE_GAIN_8 
PHIDGET_BRIDGE_GAIN_16 
PHIDGET_BRIDGE_GAIN_32 
PHIDGET_BRIDGE_GAIN_64 
PHIDGET_BRIDGE_GAIN_128 
PHIDGET_BRIDGE_GAIN_UNKNOWN 

Definition at line 340 of file phidget21.h.

Enumerator:
PHIDGET_DICTIONARY_VALUE_CHANGED 
PHIDGET_DICTIONARY_ENTRY_ADDED 
PHIDGET_DICTIONARY_ENTRY_REMOVING 
PHIDGET_DICTIONARY_CURRENT_VALUE 

Definition at line 205 of file phidget21.h.

Enumerator:
PHIDGET_FREQUENCYCOUNTER_FILTERTYPE_ZERO_CROSSING 
PHIDGET_FREQUENCYCOUNTER_FILTERTYPE_LOGIC_LEVEL 
PHIDGET_FREQUENCYCOUNTER_FILTERTYPE_UNKNOWN 

Definition at line 377 of file phidget21.h.

Enumerator:
PHIDGET_IR_ENCODING_UNKNOWN 
PHIDGET_IR_ENCODING_SPACE 
PHIDGET_IR_ENCODING_PULSE 
PHIDGET_IR_ENCODING_BIPHASE 
PHIDGET_IR_ENCODING_RC5 
PHIDGET_IR_ENCODING_RC6 

Definition at line 505 of file phidget21.h.

Enumerator:
PHIDGET_IR_LENGTH_UNKNOWN 
PHIDGET_IR_LENGTH_CONSTANT 
PHIDGET_IR_LENGTH_VARIABLE 

Definition at line 513 of file phidget21.h.

Enumerator:
PHIDGET_LED_CURRENT_LIMIT_20mA 
PHIDGET_LED_CURRENT_LIMIT_40mA 
PHIDGET_LED_CURRENT_LIMIT_60mA 
PHIDGET_LED_CURRENT_LIMIT_80mA 

Definition at line 545 of file phidget21.h.

Enumerator:
PHIDGET_LED_VOLTAGE_1_7V 
PHIDGET_LED_VOLTAGE_2_75V 
PHIDGET_LED_VOLTAGE_3_9V 
PHIDGET_LED_VOLTAGE_5_0V 

Definition at line 551 of file phidget21.h.

Enumerator:
PHIDGET_LOG_CRITICAL 
PHIDGET_LOG_ERROR 
PHIDGET_LOG_WARNING 
PHIDGET_LOG_DEBUG 
PHIDGET_LOG_INFO 
PHIDGET_LOG_VERBOSE 

Definition at line 254 of file phidget21.h.

Enumerator:
PHIDGET_TEMPERATURE_SENSOR_K_TYPE 
PHIDGET_TEMPERATURE_SENSOR_J_TYPE 
PHIDGET_TEMPERATURE_SENSOR_E_TYPE 
PHIDGET_TEMPERATURE_SENSOR_T_TYPE 

Definition at line 700 of file phidget21.h.

Enumerator:
PHIDGET_TEXTLCD_SCREEN_NONE 
PHIDGET_TEXTLCD_SCREEN_1x8 
PHIDGET_TEXTLCD_SCREEN_2x8 
PHIDGET_TEXTLCD_SCREEN_1x16 
PHIDGET_TEXTLCD_SCREEN_2x16 
PHIDGET_TEXTLCD_SCREEN_4x16 
PHIDGET_TEXTLCD_SCREEN_2x20 
PHIDGET_TEXTLCD_SCREEN_4x20 
PHIDGET_TEXTLCD_SCREEN_2x24 
PHIDGET_TEXTLCD_SCREEN_1x40 
PHIDGET_TEXTLCD_SCREEN_2x40 
PHIDGET_TEXTLCD_SCREEN_4x40 
PHIDGET_TEXTLCD_SCREEN_UNKNOWN 

Definition at line 738 of file phidget21.h.


Function Documentation

int CPhidget_enableLogging ( CPhidgetLog_level  level,
const char *  outputFile 
)
int CPhidget_getDeviceClass ( CPhidgetHandle  phid,
CPhidget_DeviceClass deviceClass 
)
int CPhidget_getDeviceID ( CPhidgetHandle  phid,
CPhidget_DeviceID deviceID 
)
int CPhidget_getDeviceLabel ( CPhidgetHandle  phid,
const char **  deviceLabel 
)
int CPhidget_getDeviceName ( CPhidgetHandle  phid,
const char **  deviceName 
)
int CPhidget_getDeviceStatus ( CPhidgetHandle  phid,
int *  deviceStatus 
)
int CPhidget_getDeviceType ( CPhidgetHandle  phid,
const char **  deviceType 
)
int CPhidget_getDeviceVersion ( CPhidgetHandle  phid,
int *  deviceVersion 
)
int CPhidget_getErrorDescription ( int  errorCode,
const char **  errorString 
)
int CPhidget_getLibraryVersion ( const char **  libraryVersion)
int CPhidget_getSerialNumber ( CPhidgetHandle  phid,
int *  serialNumber 
)
int CPhidget_getServerAddress ( CPhidgetHandle  phid,
const char **  address,
int *  port 
)
int CPhidget_getServerID ( CPhidgetHandle  phid,
const char **  serverID 
)
int CPhidget_getServerStatus ( CPhidgetHandle  phid,
int *  serverStatus 
)
int CPhidget_log ( CPhidgetLog_level  level,
const char *  id,
const char *  message,
  ... 
)
int CPhidget_open ( CPhidgetHandle  phid,
int  serialNumber 
)
int CPhidget_openLabel ( CPhidgetHandle  phid,
const char *  label 
)
int CPhidget_openLabelRemote ( CPhidgetHandle  phid,
const char *  label,
const char *  serverID,
const char *  password 
)
int CPhidget_openLabelRemoteIP ( CPhidgetHandle  phid,
const char *  label,
const char *  address,
int  port,
const char *  password 
)
int CPhidget_openRemote ( CPhidgetHandle  phid,
int  serial,
const char *  serverID,
const char *  password 
)
int CPhidget_openRemoteIP ( CPhidgetHandle  phid,
int  serial,
const char *  address,
int  port,
const char *  password 
)
int CPhidget_set_OnAttach_Handler ( CPhidgetHandle  phid,
int(*)(CPhidgetHandle phid, void *userPtr)  fptr,
void *  userPtr 
)
int CPhidget_set_OnDetach_Handler ( CPhidgetHandle  phid,
int(*)(CPhidgetHandle phid, void *userPtr)  fptr,
void *  userPtr 
)
int CPhidget_set_OnError_Handler ( CPhidgetHandle  phid,
int(*)(CPhidgetHandle phid, void *userPtr, int errorCode, const char *errorString)  fptr,
void *  userPtr 
)
int CPhidget_set_OnServerConnect_Handler ( CPhidgetHandle  phid,
int(*)(CPhidgetHandle phid, void *userPtr)  fptr,
void *  userPtr 
)
int CPhidget_set_OnServerDisconnect_Handler ( CPhidgetHandle  phid,
int(*)(CPhidgetHandle phid, void *userPtr)  fptr,
void *  userPtr 
)
int CPhidget_setDeviceLabel ( CPhidgetHandle  phid,
const char *  deviceLabel 
)
int CPhidget_waitForAttachment ( CPhidgetHandle  phid,
int  milliseconds 
)
int CPhidgetAccelerometer_getAcceleration ( CPhidgetAccelerometerHandle  phid,
int  index,
double *  acceleration 
)
int CPhidgetAccelerometer_getAccelerationChangeTrigger ( CPhidgetAccelerometerHandle  phid,
int  index,
double *  trigger 
)
int CPhidgetAccelerometer_getAccelerationMax ( CPhidgetAccelerometerHandle  phid,
int  index,
double *  max 
)
int CPhidgetAccelerometer_getAccelerationMin ( CPhidgetAccelerometerHandle  phid,
int  index,
double *  min 
)
int CPhidgetAccelerometer_set_OnAccelerationChange_Handler ( CPhidgetAccelerometerHandle  phid,
int(*)(CPhidgetAccelerometerHandle phid, void *userPtr, int index, double acceleration)  fptr,
void *  userPtr 
)
int CPhidgetAdvancedServo_getAcceleration ( CPhidgetAdvancedServoHandle  phid,
int  index,
double *  acceleration 
)
int CPhidgetAdvancedServo_getAccelerationMax ( CPhidgetAdvancedServoHandle  phid,
int  index,
double *  max 
)
int CPhidgetAdvancedServo_getAccelerationMin ( CPhidgetAdvancedServoHandle  phid,
int  index,
double *  min 
)
int CPhidgetAdvancedServo_getCurrent ( CPhidgetAdvancedServoHandle  phid,
int  index,
double *  current 
)
int CPhidgetAdvancedServo_getEngaged ( CPhidgetAdvancedServoHandle  phid,
int  index,
int *  engagedState 
)
int CPhidgetAdvancedServo_getPosition ( CPhidgetAdvancedServoHandle  phid,
int  index,
double *  position 
)
int CPhidgetAdvancedServo_getPositionMax ( CPhidgetAdvancedServoHandle  phid,
int  index,
double *  max 
)
int CPhidgetAdvancedServo_getPositionMin ( CPhidgetAdvancedServoHandle  phid,
int  index,
double *  min 
)
int CPhidgetAdvancedServo_getSpeedRampingOn ( CPhidgetAdvancedServoHandle  phid,
int  index,
int *  rampingState 
)
int CPhidgetAdvancedServo_getStopped ( CPhidgetAdvancedServoHandle  phid,
int  index,
int *  stoppedState 
)
int CPhidgetAdvancedServo_getVelocity ( CPhidgetAdvancedServoHandle  phid,
int  index,
double *  velocity 
)
int CPhidgetAdvancedServo_getVelocityLimit ( CPhidgetAdvancedServoHandle  phid,
int  index,
double *  limit 
)
int CPhidgetAdvancedServo_getVelocityMax ( CPhidgetAdvancedServoHandle  phid,
int  index,
double *  max 
)
int CPhidgetAdvancedServo_getVelocityMin ( CPhidgetAdvancedServoHandle  phid,
int  index,
double *  min 
)
int CPhidgetAdvancedServo_set_OnCurrentChange_Handler ( CPhidgetAdvancedServoHandle  phid,
int(*)(CPhidgetAdvancedServoHandle phid, void *userPtr, int index, double current)  fptr,
void *  userPtr 
)
int CPhidgetAdvancedServo_set_OnPositionChange_Handler ( CPhidgetAdvancedServoHandle  phid,
int(*)(CPhidgetAdvancedServoHandle phid, void *userPtr, int index, double position)  fptr,
void *  userPtr 
)
int CPhidgetAdvancedServo_set_OnVelocityChange_Handler ( CPhidgetAdvancedServoHandle  phid,
int(*)(CPhidgetAdvancedServoHandle phid, void *userPtr, int index, double velocity)  fptr,
void *  userPtr 
)
int CPhidgetAdvancedServo_setAcceleration ( CPhidgetAdvancedServoHandle  phid,
int  index,
double  acceleration 
)
int CPhidgetAdvancedServo_setEngaged ( CPhidgetAdvancedServoHandle  phid,
int  index,
int  engagedState 
)
int CPhidgetAdvancedServo_setPosition ( CPhidgetAdvancedServoHandle  phid,
int  index,
double  position 
)
int CPhidgetAdvancedServo_setPositionMax ( CPhidgetAdvancedServoHandle  phid,
int  index,
double  max 
)
int CPhidgetAdvancedServo_setPositionMin ( CPhidgetAdvancedServoHandle  phid,
int  index,
double  min 
)
int CPhidgetAdvancedServo_setServoParameters ( CPhidgetAdvancedServoHandle  phid,
int  index,
double  min_us,
double  max_us,
double  degrees,
double  velocity_max 
)
int CPhidgetAdvancedServo_setSpeedRampingOn ( CPhidgetAdvancedServoHandle  phid,
int  index,
int  rampingState 
)
int CPhidgetAdvancedServo_setVelocityLimit ( CPhidgetAdvancedServoHandle  phid,
int  index,
double  limit 
)
int CPhidgetAnalog_getEnabled ( CPhidgetAnalogHandle  phid,
int  index,
int *  enabledState 
)
int CPhidgetAnalog_getOutputCount ( CPhidgetAnalogHandle  phid,
int *  count 
)
int CPhidgetAnalog_getVoltage ( CPhidgetAnalogHandle  phid,
int  index,
double *  voltage 
)
int CPhidgetAnalog_getVoltageMax ( CPhidgetAnalogHandle  phid,
int  index,
double *  max 
)
int CPhidgetAnalog_getVoltageMin ( CPhidgetAnalogHandle  phid,
int  index,
double *  min 
)
int CPhidgetAnalog_setEnabled ( CPhidgetAnalogHandle  phid,
int  index,
int  enabledState 
)
int CPhidgetAnalog_setVoltage ( CPhidgetAnalogHandle  phid,
int  index,
double  voltage 
)
int CPhidgetBridge_getBridgeMax ( CPhidgetBridgeHandle  phid,
int  index,
double *  max 
)
int CPhidgetBridge_getBridgeMin ( CPhidgetBridgeHandle  phid,
int  index,
double *  min 
)
int CPhidgetBridge_getBridgeValue ( CPhidgetBridgeHandle  phid,
int  index,
double *  value 
)
int CPhidgetBridge_getDataRate ( CPhidgetBridgeHandle  phid,
int *  milliseconds 
)
int CPhidgetBridge_getDataRateMax ( CPhidgetBridgeHandle  phid,
int *  max 
)
int CPhidgetBridge_getDataRateMin ( CPhidgetBridgeHandle  phid,
int *  min 
)
int CPhidgetBridge_getEnabled ( CPhidgetBridgeHandle  phid,
int  index,
int *  enabledState 
)
int CPhidgetBridge_getGain ( CPhidgetBridgeHandle  phid,
int  index,
CPhidgetBridge_Gain gain 
)
int CPhidgetBridge_getInputCount ( CPhidgetBridgeHandle  phid,
int *  count 
)
int CPhidgetBridge_set_OnBridgeData_Handler ( CPhidgetBridgeHandle  phid,
int(*)(CPhidgetBridgeHandle phid, void *userPtr, int index, double value)  fptr,
void *  userPtr 
)
int CPhidgetBridge_setDataRate ( CPhidgetBridgeHandle  phid,
int  milliseconds 
)
int CPhidgetBridge_setEnabled ( CPhidgetBridgeHandle  phid,
int  index,
int  enabledState 
)
int CPhidgetBridge_setGain ( CPhidgetBridgeHandle  phid,
int  index,
CPhidgetBridge_Gain  gain 
)
int CPhidgetDictionary_addKey ( CPhidgetDictionaryHandle  dict,
const char *  key,
const char *  value,
int  persistent 
)
int CPhidgetDictionary_getKey ( CPhidgetDictionaryHandle  dict,
const char *  key,
char *  value,
int  valuelen 
)
int CPhidgetDictionary_getServerAddress ( CPhidgetDictionaryHandle  dict,
const char **  address,
int *  port 
)
int CPhidgetDictionary_getServerID ( CPhidgetDictionaryHandle  dict,
const char **  serverID 
)
int CPhidgetDictionary_getServerStatus ( CPhidgetDictionaryHandle  dict,
int *  serverStatus 
)
int CPhidgetDictionary_openRemote ( CPhidgetDictionaryHandle  dict,
const char *  serverID,
const char *  password 
)
int CPhidgetDictionary_openRemoteIP ( CPhidgetDictionaryHandle  dict,
const char *  address,
int  port,
const char *  password 
)
int CPhidgetDictionary_removeKey ( CPhidgetDictionaryHandle  dict,
const char *  pattern 
)
int CPhidgetDictionary_set_OnError_Handler ( CPhidgetDictionaryHandle  dict,
int(*)(CPhidgetDictionaryHandle, void *userPtr, int errorCode, const char *errorString)  fptr,
void *  userPtr 
)
int CPhidgetDictionary_set_OnServerConnect_Handler ( CPhidgetDictionaryHandle  dict,
int(*)(CPhidgetDictionaryHandle dict, void *userPtr)  fptr,
void *  userPtr 
)
int CPhidgetDictionary_set_OnServerDisconnect_Handler ( CPhidgetDictionaryHandle  dict,
int(*)(CPhidgetDictionaryHandle dict, void *userPtr)  fptr,
void *  userPtr 
)
int CPhidgetEncoder_getEnabled ( CPhidgetEncoderHandle  phid,
int  index,
int *  enabledState 
)
int CPhidgetEncoder_getEncoderCount ( CPhidgetEncoderHandle  phid,
int *  count 
)
int CPhidgetEncoder_getIndexPosition ( CPhidgetEncoderHandle  phid,
int  index,
int *  position 
)
int CPhidgetEncoder_getInputCount ( CPhidgetEncoderHandle  phid,
int *  count 
)
int CPhidgetEncoder_getInputState ( CPhidgetEncoderHandle  phid,
int  index,
int *  inputState 
)
int CPhidgetEncoder_getPosition ( CPhidgetEncoderHandle  phid,
int  index,
int *  position 
)
int CPhidgetEncoder_set_OnIndexChange_Handler ( CPhidgetEncoderHandle  phid,
int(*)(CPhidgetEncoderHandle phid, void *userPtr, int index, int indexPosition)  fptr,
void *  userPtr 
)
int CPhidgetEncoder_set_OnInputChange_Handler ( CPhidgetEncoderHandle  phid,
int(*)(CPhidgetEncoderHandle phid, void *userPtr, int index, int inputState)  fptr,
void *  userPtr 
)
int CPhidgetEncoder_set_OnPositionChange_Handler ( CPhidgetEncoderHandle  phid,
int(*)(CPhidgetEncoderHandle phid, void *userPtr, int index, int time, int positionChange)  fptr,
void *  userPtr 
)
int CPhidgetEncoder_setEnabled ( CPhidgetEncoderHandle  phid,
int  index,
int  enabledState 
)
int CPhidgetEncoder_setPosition ( CPhidgetEncoderHandle  phid,
int  index,
int  position 
)
int CPhidgetFrequencyCounter_getEnabled ( CPhidgetFrequencyCounterHandle  phid,
int  index,
int *  enabledState 
)
int CPhidgetFrequencyCounter_getFrequency ( CPhidgetFrequencyCounterHandle  phid,
int  index,
double *  frequency 
)
int CPhidgetFrequencyCounter_getTimeout ( CPhidgetFrequencyCounterHandle  phid,
int  index,
int *  timeout 
)
int CPhidgetFrequencyCounter_set_OnCount_Handler ( CPhidgetFrequencyCounterHandle  phid,
int(*)(CPhidgetFrequencyCounterHandle phid, void *userPtr, int index, int time, int counts)  fptr,
void *  userPtr 
)
int CPhidgetFrequencyCounter_setEnabled ( CPhidgetFrequencyCounterHandle  phid,
int  index,
int  enabledState 
)
int CPhidgetFrequencyCounter_setTimeout ( CPhidgetFrequencyCounterHandle  phid,
int  index,
int  timeout 
)
int CPhidgetGPS_getAltitude ( CPhidgetGPSHandle  phid,
double *  altitude 
)
int CPhidgetGPS_getDate ( CPhidgetGPSHandle  phid,
GPSDate date 
)
int CPhidgetGPS_getHeading ( CPhidgetGPSHandle  phid,
double *  heading 
)
int CPhidgetGPS_getLatitude ( CPhidgetGPSHandle  phid,
double *  latitude 
)
int CPhidgetGPS_getLongitude ( CPhidgetGPSHandle  phid,
double *  longitude 
)
int CPhidgetGPS_getPositionFixStatus ( CPhidgetGPSHandle  phid,
int *  fixStatus 
)
int CPhidgetGPS_getTime ( CPhidgetGPSHandle  phid,
GPSTime time 
)
int CPhidgetGPS_getVelocity ( CPhidgetGPSHandle  phid,
double *  velocity 
)
int CPhidgetGPS_set_OnPositionChange_Handler ( CPhidgetGPSHandle  phid,
int(*)(CPhidgetGPSHandle phid, void *userPtr, double latitude, double longitude, double altitude)  fptr,
void *  userPtr 
)
int CPhidgetGPS_set_OnPositionFixStatusChange_Handler ( CPhidgetGPSHandle  phid,
int(*)(CPhidgetGPSHandle phid, void *userPtr, int status)  fptr,
void *  userPtr 
)
int CPhidgetInterfaceKit_getDataRate ( CPhidgetInterfaceKitHandle  phid,
int  index,
int *  milliseconds 
)
int CPhidgetInterfaceKit_getDataRateMax ( CPhidgetInterfaceKitHandle  phid,
int  index,
int *  max 
)
int CPhidgetInterfaceKit_getDataRateMin ( CPhidgetInterfaceKitHandle  phid,
int  index,
int *  min 
)
int CPhidgetInterfaceKit_getInputState ( CPhidgetInterfaceKitHandle  phid,
int  index,
int *  inputState 
)
int CPhidgetInterfaceKit_getOutputState ( CPhidgetInterfaceKitHandle  phid,
int  index,
int *  outputState 
)
int CPhidgetInterfaceKit_getRatiometric ( CPhidgetInterfaceKitHandle  phid,
int *  ratiometric 
)
int CPhidgetInterfaceKit_getSensorChangeTrigger ( CPhidgetInterfaceKitHandle  phid,
int  index,
int *  trigger 
)
int CPhidgetInterfaceKit_getSensorRawValue ( CPhidgetInterfaceKitHandle  phid,
int  index,
int *  sensorRawValue 
)
int CPhidgetInterfaceKit_getSensorValue ( CPhidgetInterfaceKitHandle  phid,
int  index,
int *  sensorValue 
)
int CPhidgetInterfaceKit_set_OnInputChange_Handler ( CPhidgetInterfaceKitHandle  phid,
int(*)(CPhidgetInterfaceKitHandle phid, void *userPtr, int index, int inputState)  fptr,
void *  userPtr 
)
int CPhidgetInterfaceKit_set_OnOutputChange_Handler ( CPhidgetInterfaceKitHandle  phid,
int(*)(CPhidgetInterfaceKitHandle phid, void *userPtr, int index, int outputState)  fptr,
void *  userPtr 
)
int CPhidgetInterfaceKit_set_OnSensorChange_Handler ( CPhidgetInterfaceKitHandle  phid,
int(*)(CPhidgetInterfaceKitHandle phid, void *userPtr, int index, int sensorValue)  fptr,
void *  userPtr 
)
int CPhidgetInterfaceKit_setDataRate ( CPhidgetInterfaceKitHandle  phid,
int  index,
int  milliseconds 
)
int CPhidgetInterfaceKit_setOutputState ( CPhidgetInterfaceKitHandle  phid,
int  index,
int  outputState 
)
int CPhidgetInterfaceKit_setSensorChangeTrigger ( CPhidgetInterfaceKitHandle  phid,
int  index,
int  trigger 
)
int CPhidgetIR_getLastCode ( CPhidgetIRHandle  phid,
unsigned char *  data,
int *  dataLength,
int *  bitCount 
)
int CPhidgetIR_getLastLearnedCode ( CPhidgetIRHandle  phid,
unsigned char *  data,
int *  dataLength,
CPhidgetIR_CodeInfo codeInfo 
)
int CPhidgetIR_getRawData ( CPhidgetIRHandle  phid,
int *  data,
int *  dataLength 
)
int CPhidgetIR_set_OnCode_Handler ( CPhidgetIRHandle  phid,
int(*)(CPhidgetIRHandle phid, void *userPtr, unsigned char *data, int dataLength, int bitCount, int repeat)  fptr,
void *  userPtr 
)
int CPhidgetIR_set_OnLearn_Handler ( CPhidgetIRHandle  phid,
int(*)(CPhidgetIRHandle phid, void *userPtr, unsigned char *data, int dataLength, CPhidgetIR_CodeInfoHandle codeInfo)  fptr,
void *  userPtr 
)
int CPhidgetIR_set_OnRawData_Handler ( CPhidgetIRHandle  phid,
int(*)(CPhidgetIRHandle phid, void *userPtr, int *data, int dataLength)  fptr,
void *  userPtr 
)
int CPhidgetIR_Transmit ( CPhidgetIRHandle  phid,
unsigned char *  data,
CPhidgetIR_CodeInfoHandle  codeInfo 
)
int CPhidgetIR_TransmitRaw ( CPhidgetIRHandle  phid,
int *  data,
int  length,
int  carrierFrequency,
int  dutyCycle,
int  gap 
)
int CPhidgetLED_getDiscreteLED ( CPhidgetLEDHandle  phid,
int  index,
int *  brightness 
)
int CPhidgetLED_getLEDCount ( CPhidgetLEDHandle  phid,
int *  count 
)
int CPhidgetLED_setDiscreteLED ( CPhidgetLEDHandle  phid,
int  index,
int  brightness 
)
int CPhidgetManager_getAttachedDevices ( CPhidgetManagerHandle  phidm,
CPhidgetHandle phidArray[],
int *  count 
)
int CPhidgetManager_getServerAddress ( CPhidgetManagerHandle  phidm,
const char **  address,
int *  port 
)
int CPhidgetManager_getServerID ( CPhidgetManagerHandle  phidm,
const char **  serverID 
)
int CPhidgetManager_getServerStatus ( CPhidgetManagerHandle  phidm,
int *  serverStatus 
)
int CPhidgetManager_openRemote ( CPhidgetManagerHandle  phidm,
const char *  serverID,
const char *  password 
)
int CPhidgetManager_openRemoteIP ( CPhidgetManagerHandle  phidm,
const char *  address,
int  port,
const char *  password 
)
int CPhidgetManager_set_OnAttach_Handler ( CPhidgetManagerHandle  phidm,
int(*)(CPhidgetHandle phid, void *userPtr)  fptr,
void *  userPtr 
)
int CPhidgetManager_set_OnDetach_Handler ( CPhidgetManagerHandle  phidm,
int(*)(CPhidgetHandle phid, void *userPtr)  fptr,
void *  userPtr 
)
int CPhidgetManager_set_OnError_Handler ( CPhidgetManagerHandle  phidm,
int(*)(CPhidgetManagerHandle phidm, void *userPtr, int errorCode, const char *errorString)  fptr,
void *  userPtr 
)
int CPhidgetManager_set_OnServerConnect_Handler ( CPhidgetManagerHandle  phidm,
int(*)(CPhidgetManagerHandle phidm, void *userPtr)  fptr,
void *  userPtr 
)
int CPhidgetManager_set_OnServerDisconnect_Handler ( CPhidgetManagerHandle  phidm,
int(*)(CPhidgetManagerHandle phidm, void *userPtr)  fptr,
void *  userPtr 
)
int CPhidgetMotorControl_getAcceleration ( CPhidgetMotorControlHandle  phid,
int  index,
double *  acceleration 
)
int CPhidgetMotorControl_getAccelerationMax ( CPhidgetMotorControlHandle  phid,
int  index,
double *  max 
)
int CPhidgetMotorControl_getAccelerationMin ( CPhidgetMotorControlHandle  phid,
int  index,
double *  min 
)
int CPhidgetMotorControl_getBackEMF ( CPhidgetMotorControlHandle  phid,
int  index,
double *  voltage 
)
int CPhidgetMotorControl_getBackEMFSensingState ( CPhidgetMotorControlHandle  phid,
int  index,
int *  bEMFState 
)
int CPhidgetMotorControl_getBraking ( CPhidgetMotorControlHandle  phid,
int  index,
double *  braking 
)
int CPhidgetMotorControl_getCurrent ( CPhidgetMotorControlHandle  phid,
int  index,
double *  current 
)
int CPhidgetMotorControl_getEncoderPosition ( CPhidgetMotorControlHandle  phid,
int  index,
int *  position 
)
int CPhidgetMotorControl_getInputState ( CPhidgetMotorControlHandle  phid,
int  index,
int *  inputState 
)
int CPhidgetMotorControl_getRatiometric ( CPhidgetMotorControlHandle  phid,
int *  ratiometric 
)
int CPhidgetMotorControl_getSensorRawValue ( CPhidgetMotorControlHandle  phid,
int  index,
int *  sensorRawValue 
)
int CPhidgetMotorControl_getSensorValue ( CPhidgetMotorControlHandle  phid,
int  index,
int *  sensorValue 
)
int CPhidgetMotorControl_getSupplyVoltage ( CPhidgetMotorControlHandle  phid,
double *  supplyVoltage 
)
int CPhidgetMotorControl_getVelocity ( CPhidgetMotorControlHandle  phid,
int  index,
double *  velocity 
)
int CPhidgetMotorControl_set_OnBackEMFUpdate_Handler ( CPhidgetMotorControlHandle  phid,
int(*)(CPhidgetMotorControlHandle phid, void *userPtr, int index, double voltage)  fptr,
void *  userPtr 
)
int CPhidgetMotorControl_set_OnCurrentChange_Handler ( CPhidgetMotorControlHandle  phid,
int(*)(CPhidgetMotorControlHandle phid, void *userPtr, int index, double current)  fptr,
void *  userPtr 
)
int CPhidgetMotorControl_set_OnCurrentUpdate_Handler ( CPhidgetMotorControlHandle  phid,
int(*)(CPhidgetMotorControlHandle phid, void *userPtr, int index, double current)  fptr,
void *  userPtr 
)
int CPhidgetMotorControl_set_OnEncoderPositionChange_Handler ( CPhidgetMotorControlHandle  phid,
int(*)(CPhidgetMotorControlHandle phid, void *userPtr, int index, int time, int positionChange)  fptr,
void *  userPtr 
)
int CPhidgetMotorControl_set_OnEncoderPositionUpdate_Handler ( CPhidgetMotorControlHandle  phid,
int(*)(CPhidgetMotorControlHandle phid, void *userPtr, int index, int positionChange)  fptr,
void *  userPtr 
)
int CPhidgetMotorControl_set_OnInputChange_Handler ( CPhidgetMotorControlHandle  phid,
int(*)(CPhidgetMotorControlHandle phid, void *userPtr, int index, int inputState)  fptr,
void *  userPtr 
)
int CPhidgetMotorControl_set_OnSensorUpdate_Handler ( CPhidgetMotorControlHandle  phid,
int(*)(CPhidgetMotorControlHandle phid, void *userPtr, int index, int sensorValue)  fptr,
void *  userPtr 
)
int CPhidgetMotorControl_set_OnVelocityChange_Handler ( CPhidgetMotorControlHandle  phid,
int(*)(CPhidgetMotorControlHandle phid, void *userPtr, int index, double velocity)  fptr,
void *  userPtr 
)
int CPhidgetMotorControl_setAcceleration ( CPhidgetMotorControlHandle  phid,
int  index,
double  acceleration 
)
int CPhidgetMotorControl_setBackEMFSensingState ( CPhidgetMotorControlHandle  phid,
int  index,
int  bEMFState 
)
int CPhidgetMotorControl_setBraking ( CPhidgetMotorControlHandle  phid,
int  index,
double  braking 
)
int CPhidgetMotorControl_setEncoderPosition ( CPhidgetMotorControlHandle  phid,
int  index,
int  position 
)
int CPhidgetMotorControl_setVelocity ( CPhidgetMotorControlHandle  phid,
int  index,
double  velocity 
)
int CPhidgetPHSensor_getPH ( CPhidgetPHSensorHandle  phid,
double *  ph 
)
int CPhidgetPHSensor_getPHChangeTrigger ( CPhidgetPHSensorHandle  phid,
double *  trigger 
)
int CPhidgetPHSensor_getPHMax ( CPhidgetPHSensorHandle  phid,
double *  max 
)
int CPhidgetPHSensor_getPHMin ( CPhidgetPHSensorHandle  phid,
double *  min 
)
int CPhidgetPHSensor_getPotential ( CPhidgetPHSensorHandle  phid,
double *  potential 
)
int CPhidgetPHSensor_getPotentialMax ( CPhidgetPHSensorHandle  phid,
double *  max 
)
int CPhidgetPHSensor_getPotentialMin ( CPhidgetPHSensorHandle  phid,
double *  min 
)
int CPhidgetPHSensor_set_OnPHChange_Handler ( CPhidgetPHSensorHandle  phid,
int(*)(CPhidgetPHSensorHandle phid, void *userPtr, double ph)  fptr,
void *  userPtr 
)
int CPhidgetPHSensor_setPHChangeTrigger ( CPhidgetPHSensorHandle  phid,
double  trigger 
)
int CPhidgetPHSensor_setTemperature ( CPhidgetPHSensorHandle  phid,
double  temperature 
)
int CPhidgetRFID_getAntennaOn ( CPhidgetRFIDHandle  phid,
int *  antennaState 
)
int CPhidgetRFID_getLastTag ( CPhidgetRFIDHandle  phid,
unsigned char *  tag 
)
int CPhidgetRFID_getLEDOn ( CPhidgetRFIDHandle  phid,
int *  LEDState 
)
int CPhidgetRFID_getOutputCount ( CPhidgetRFIDHandle  phid,
int *  count 
)
int CPhidgetRFID_getOutputState ( CPhidgetRFIDHandle  phid,
int  index,
int *  outputState 
)
int CPhidgetRFID_getTagStatus ( CPhidgetRFIDHandle  phid,
int *  status 
)
int CPhidgetRFID_set_OnOutputChange_Handler ( CPhidgetRFIDHandle  phid,
int(*)(CPhidgetRFIDHandle phid, void *userPtr, int index, int outputState)  fptr,
void *  userPtr 
)
int CPhidgetRFID_set_OnTag_Handler ( CPhidgetRFIDHandle  phid,
int(*)(CPhidgetRFIDHandle phid, void *userPtr, unsigned char *tag)  fptr,
void *  userPtr 
)
int CPhidgetRFID_set_OnTagLost_Handler ( CPhidgetRFIDHandle  phid,
int(*)(CPhidgetRFIDHandle phid, void *userPtr, unsigned char *tag)  fptr,
void *  userPtr 
)
int CPhidgetRFID_setAntennaOn ( CPhidgetRFIDHandle  phid,
int  antennaState 
)
int CPhidgetRFID_setLEDOn ( CPhidgetRFIDHandle  phid,
int  LEDState 
)
int CPhidgetRFID_setOutputState ( CPhidgetRFIDHandle  phid,
int  index,
int  outputState 
)
int CPhidgetServo_getEngaged ( CPhidgetServoHandle  phid,
int  index,
int *  engagedState 
)
int CPhidgetServo_getMotorCount ( CPhidgetServoHandle  phid,
int *  count 
)
int CPhidgetServo_getPosition ( CPhidgetServoHandle  phid,
int  index,
double *  position 
)
int CPhidgetServo_getPositionMax ( CPhidgetServoHandle  phid,
int  index,
double *  max 
)
int CPhidgetServo_getPositionMin ( CPhidgetServoHandle  phid,
int  index,
double *  min 
)
int CPhidgetServo_getServoType ( CPhidgetServoHandle  phid,
int  index,
CPhidget_ServoType servoType 
)
int CPhidgetServo_set_OnPositionChange_Handler ( CPhidgetServoHandle  phid,
int(*)(CPhidgetServoHandle phid, void *userPtr, int index, double position)  fptr,
void *  userPtr 
)
int CPhidgetServo_setEngaged ( CPhidgetServoHandle  phid,
int  index,
int  engagedState 
)
int CPhidgetServo_setPosition ( CPhidgetServoHandle  phid,
int  index,
double  position 
)
int CPhidgetServo_setServoParameters ( CPhidgetServoHandle  phid,
int  index,
double  min_us,
double  max_us,
double  degrees 
)
int CPhidgetServo_setServoType ( CPhidgetServoHandle  phid,
int  index,
CPhidget_ServoType  servoType 
)
int CPhidgetSpatial_getAcceleration ( CPhidgetSpatialHandle  phid,
int  index,
double *  acceleration 
)
int CPhidgetSpatial_getAccelerationMax ( CPhidgetSpatialHandle  phid,
int  index,
double *  max 
)
int CPhidgetSpatial_getAccelerationMin ( CPhidgetSpatialHandle  phid,
int  index,
double *  min 
)
int CPhidgetSpatial_getAngularRate ( CPhidgetSpatialHandle  phid,
int  index,
double *  angularRate 
)
int CPhidgetSpatial_getAngularRateMax ( CPhidgetSpatialHandle  phid,
int  index,
double *  max 
)
int CPhidgetSpatial_getAngularRateMin ( CPhidgetSpatialHandle  phid,
int  index,
double *  min 
)
int CPhidgetSpatial_getDataRate ( CPhidgetSpatialHandle  phid,
int *  milliseconds 
)
int CPhidgetSpatial_getMagneticField ( CPhidgetSpatialHandle  phid,
int  index,
double *  magneticField 
)
int CPhidgetSpatial_getMagneticFieldMax ( CPhidgetSpatialHandle  phid,
int  index,
double *  max 
)
int CPhidgetSpatial_getMagneticFieldMin ( CPhidgetSpatialHandle  phid,
int  index,
double *  min 
)
int CPhidgetSpatial_set_OnSpatialData_Handler ( CPhidgetSpatialHandle  phid,
int(*)(CPhidgetSpatialHandle phid, void *userPtr, CPhidgetSpatial_SpatialEventDataHandle *data, int dataCount)  fptr,
void *  userPtr 
)
int CPhidgetSpatial_setCompassCorrectionParameters ( CPhidgetSpatialHandle  phid,
double  magField,
double  offset0,
double  offset1,
double  offset2,
double  gain0,
double  gain1,
double  gain2,
double  T0,
double  T1,
double  T2,
double  T3,
double  T4,
double  T5 
)
int CPhidgetSpatial_setDataRate ( CPhidgetSpatialHandle  phid,
int  milliseconds 
)
int CPhidgetStepper_getAcceleration ( CPhidgetStepperHandle  phid,
int  index,
double *  acceleration 
)
int CPhidgetStepper_getAccelerationMax ( CPhidgetStepperHandle  phid,
int  index,
double *  max 
)
int CPhidgetStepper_getAccelerationMin ( CPhidgetStepperHandle  phid,
int  index,
double *  min 
)
int CPhidgetStepper_getCurrent ( CPhidgetStepperHandle  phid,
int  index,
double *  current 
)
int CPhidgetStepper_getCurrentLimit ( CPhidgetStepperHandle  phid,
int  index,
double *  limit 
)
int CPhidgetStepper_getCurrentMax ( CPhidgetStepperHandle  phid,
int  index,
double *  max 
)
int CPhidgetStepper_getCurrentMin ( CPhidgetStepperHandle  phid,
int  index,
double *  min 
)
int CPhidgetStepper_getCurrentPosition ( CPhidgetStepperHandle  phid,
int  index,
__int64 position 
)
int CPhidgetStepper_getEngaged ( CPhidgetStepperHandle  phid,
int  index,
int *  engagedState 
)
int CPhidgetStepper_getInputCount ( CPhidgetStepperHandle  phid,
int *  count 
)
int CPhidgetStepper_getInputState ( CPhidgetStepperHandle  phid,
int  index,
int *  inputState 
)
int CPhidgetStepper_getMotorCount ( CPhidgetStepperHandle  phid,
int *  count 
)
int CPhidgetStepper_getPositionMax ( CPhidgetStepperHandle  phid,
int  index,
__int64 max 
)
int CPhidgetStepper_getPositionMin ( CPhidgetStepperHandle  phid,
int  index,
__int64 min 
)
int CPhidgetStepper_getStopped ( CPhidgetStepperHandle  phid,
int  index,
int *  stoppedState 
)
int CPhidgetStepper_getTargetPosition ( CPhidgetStepperHandle  phid,
int  index,
__int64 position 
)
int CPhidgetStepper_getVelocity ( CPhidgetStepperHandle  phid,
int  index,
double *  velocity 
)
int CPhidgetStepper_getVelocityLimit ( CPhidgetStepperHandle  phid,
int  index,
double *  limit 
)
int CPhidgetStepper_getVelocityMax ( CPhidgetStepperHandle  phid,
int  index,
double *  max 
)
int CPhidgetStepper_getVelocityMin ( CPhidgetStepperHandle  phid,
int  index,
double *  min 
)
int CPhidgetStepper_set_OnCurrentChange_Handler ( CPhidgetStepperHandle  phid,
int(*)(CPhidgetStepperHandle phid, void *userPtr, int index, double current)  fptr,
void *  userPtr 
)
int CPhidgetStepper_set_OnInputChange_Handler ( CPhidgetStepperHandle  phid,
int(*)(CPhidgetStepperHandle phid, void *userPtr, int index, int inputState)  fptr,
void *  userPtr 
)
int CPhidgetStepper_set_OnPositionChange_Handler ( CPhidgetStepperHandle  phid,
int(*)(CPhidgetStepperHandle phid, void *userPtr, int index, __int64 position)  fptr,
void *  userPtr 
)
int CPhidgetStepper_set_OnVelocityChange_Handler ( CPhidgetStepperHandle  phid,
int(*)(CPhidgetStepperHandle phid, void *userPtr, int index, double velocity)  fptr,
void *  userPtr 
)
int CPhidgetStepper_setAcceleration ( CPhidgetStepperHandle  phid,
int  index,
double  acceleration 
)
int CPhidgetStepper_setCurrentLimit ( CPhidgetStepperHandle  phid,
int  index,
double  limit 
)
int CPhidgetStepper_setCurrentPosition ( CPhidgetStepperHandle  phid,
int  index,
__int64  position 
)
int CPhidgetStepper_setEngaged ( CPhidgetStepperHandle  phid,
int  index,
int  engagedState 
)
int CPhidgetStepper_setTargetPosition ( CPhidgetStepperHandle  phid,
int  index,
__int64  position 
)
int CPhidgetStepper_setVelocityLimit ( CPhidgetStepperHandle  phid,
int  index,
double  limit 
)
int CPhidgetTemperatureSensor_getPotential ( CPhidgetTemperatureSensorHandle  phid,
int  index,
double *  potential 
)
int CPhidgetTemperatureSensor_getPotentialMax ( CPhidgetTemperatureSensorHandle  phid,
int  index,
double *  max 
)
int CPhidgetTemperatureSensor_getPotentialMin ( CPhidgetTemperatureSensorHandle  phid,
int  index,
double *  min 
)
int CPhidgetTemperatureSensor_getTemperature ( CPhidgetTemperatureSensorHandle  phid,
int  index,
double *  temperature 
)
int CPhidgetTemperatureSensor_set_OnTemperatureChange_Handler ( CPhidgetTemperatureSensorHandle  phid,
int(*)(CPhidgetTemperatureSensorHandle phid, void *userPtr, int index, double temperature)  fptr,
void *  userPtr 
)
int CPhidgetTextLCD_getBacklight ( CPhidgetTextLCDHandle  phid,
int *  backlightState 
)
int CPhidgetTextLCD_getBrightness ( CPhidgetTextLCDHandle  phid,
int *  brightness 
)
int CPhidgetTextLCD_getColumnCount ( CPhidgetTextLCDHandle  phid,
int *  count 
)
int CPhidgetTextLCD_getContrast ( CPhidgetTextLCDHandle  phid,
int *  contrast 
)
int CPhidgetTextLCD_getCursorBlink ( CPhidgetTextLCDHandle  phid,
int *  cursorBlinkState 
)
int CPhidgetTextLCD_getCursorOn ( CPhidgetTextLCDHandle  phid,
int *  cursorState 
)
int CPhidgetTextLCD_getRowCount ( CPhidgetTextLCDHandle  phid,
int *  count 
)
int CPhidgetTextLCD_getScreen ( CPhidgetTextLCDHandle  phid,
int *  screenIndex 
)
int CPhidgetTextLCD_getScreenCount ( CPhidgetTextLCDHandle  phid,
int *  count 
)
int CPhidgetTextLCD_setBacklight ( CPhidgetTextLCDHandle  phid,
int  backlightState 
)
int CPhidgetTextLCD_setBrightness ( CPhidgetTextLCDHandle  phid,
int  brightness 
)
int CPhidgetTextLCD_setContrast ( CPhidgetTextLCDHandle  phid,
int  contrast 
)
int CPhidgetTextLCD_setCursorBlink ( CPhidgetTextLCDHandle  phid,
int  cursorBlinkState 
)
int CPhidgetTextLCD_setCursorOn ( CPhidgetTextLCDHandle  phid,
int  cursorState 
)
int CPhidgetTextLCD_setCustomCharacter ( CPhidgetTextLCDHandle  phid,
int  index,
int  var1,
int  var2 
)
int CPhidgetTextLCD_setDisplayCharacter ( CPhidgetTextLCDHandle  phid,
int  index,
int  column,
unsigned char  character 
)
int CPhidgetTextLCD_setDisplayString ( CPhidgetTextLCDHandle  phid,
int  index,
char *  displayString 
)
int CPhidgetTextLCD_setScreen ( CPhidgetTextLCDHandle  phid,
int  screenIndex 
)
int CPhidgetTextLED_getBrightness ( CPhidgetTextLEDHandle  phid,
int *  brightness 
)
int CPhidgetTextLED_getColumnCount ( CPhidgetTextLEDHandle  phid,
int *  count 
)
int CPhidgetTextLED_getRowCount ( CPhidgetTextLEDHandle  phid,
int *  count 
)
int CPhidgetTextLED_setBrightness ( CPhidgetTextLEDHandle  phid,
int  brightness 
)
int CPhidgetTextLED_setDisplayString ( CPhidgetTextLEDHandle  phid,
int  index,
char *  displayString 
)
int CPhidgetWeightSensor_getWeight ( CPhidgetWeightSensorHandle  phid,
double *  weight 
)
int CPhidgetWeightSensor_set_OnWeightChange_Handler ( CPhidgetWeightSensorHandle  phid,
int(*)(CPhidgetWeightSensorHandle phid, void *userPtr, double weight)  fptr,
void *  userPtr 
)


libphidgets
Author(s): Alexander Bubeck
autogenerated on Fri Aug 28 2015 10:21:53