phidget21.h
Go to the documentation of this file.
00001 #ifdef __cplusplus
00002 extern "C" {
00003 #endif
00004  
00005 #if defined(__stdcall)  
00006  #define CCONV __stdcall        
00007 #else 
00008  #if defined(__BORLANDC__) || defined(_MSC_VER) 
00009   #define CCONV __stdcall  
00010  #else 
00011   #define CCONV 
00012  #endif 
00013 #endif 
00014  
00015 #if !defined(__int64) 
00016 #if !defined(__BORLANDC__) && !defined(_MSC_VER) 
00017 typedef long long __int64; 
00018 #endif 
00019 #endif
00020 
00021  
00022 typedef struct _CPhidget *CPhidgetHandle;
00023 typedef struct _CPhidget_Timestamp {
00024  int seconds;
00025  int microseconds;
00026 } CPhidget_Timestamp, *CPhidget_TimestampHandle;
00027 typedef enum {
00028  PHIDCLASS_ACCELEROMETER = 2,
00029  PHIDCLASS_ADVANCEDSERVO = 3,
00030  PHIDCLASS_ANALOG = 22,
00031  PHIDCLASS_BRIDGE = 23,
00032  PHIDCLASS_ENCODER = 4,
00033  PHIDCLASS_FREQUENCYCOUNTER = 21,
00034  PHIDCLASS_GPS = 5,
00035  PHIDCLASS_INTERFACEKIT = 7,
00036  PHIDCLASS_IR = 19,
00037  PHIDCLASS_LED = 8,
00038  PHIDCLASS_MOTORCONTROL = 9,
00039  PHIDCLASS_PHSENSOR = 10,
00040  PHIDCLASS_RFID = 11,
00041  PHIDCLASS_SERVO = 12,
00042  PHIDCLASS_SPATIAL = 20,
00043  PHIDCLASS_STEPPER = 13,
00044  PHIDCLASS_TEMPERATURESENSOR = 14,
00045  PHIDCLASS_TEXTLCD = 15,
00046  PHIDCLASS_TEXTLED = 16,
00047  PHIDCLASS_WEIGHTSENSOR = 17,
00048 } CPhidget_DeviceClass;
00049 typedef enum {
00050  PHIDID_ACCELEROMETER_3AXIS = 0x07E,
00051  PHIDID_ADVANCEDSERVO_1MOTOR = 0x082,
00052  PHIDID_ADVANCEDSERVO_8MOTOR = 0x03A,
00053  PHIDID_ANALOG_4OUTPUT = 0x037,
00054  PHIDID_BIPOLAR_STEPPER_1MOTOR = 0x07B,
00055  PHIDID_BRIDGE_4INPUT = 0x03B,
00056  PHIDID_ENCODER_1ENCODER_1INPUT = 0x04B,
00057  PHIDID_ENCODER_HS_1ENCODER = 0x080,
00058  PHIDID_ENCODER_HS_4ENCODER_4INPUT = 0x04F,
00059  PHIDID_FREQUENCYCOUNTER_2INPUT = 0x035,
00060  PHIDID_GPS = 0x079,
00061  PHIDID_INTERFACEKIT_0_0_4 = 0x040,
00062  PHIDID_INTERFACEKIT_0_0_8 = 0x081,
00063  PHIDID_INTERFACEKIT_0_16_16 = 0x044,
00064  PHIDID_INTERFACEKIT_2_2_2 = 0x036,
00065  PHIDID_INTERFACEKIT_8_8_8 = 0x045,
00066  PHIDID_INTERFACEKIT_8_8_8_w_LCD = 0x07D,
00067  PHIDID_IR = 0x04D,
00068  PHIDID_LED_64_ADV = 0x04C,
00069  PHIDID_LINEAR_TOUCH = 0x076,
00070  PHIDID_MOTORCONTROL_1MOTOR = 0x03E,
00071  PHIDID_MOTORCONTROL_HC_2MOTOR = 0x059,
00072  PHIDID_RFID_2OUTPUT = 0x031,
00073  PHIDID_ROTARY_TOUCH = 0x077,
00074  PHIDID_SPATIAL_ACCEL_3AXIS = 0x07F,
00075  PHIDID_SPATIAL_ACCEL_GYRO_COMPASS = 0x033,
00076  PHIDID_TEMPERATURESENSOR = 0x070,
00077  PHIDID_TEMPERATURESENSOR_4 = 0x032,
00078  PHIDID_TEMPERATURESENSOR_IR = 0x03C,
00079  PHIDID_TEXTLCD_2x20_w_8_8_8 = 0x17D,
00080  PHIDID_TEXTLCD_ADAPTER = 0x03D,
00081  PHIDID_UNIPOLAR_STEPPER_4MOTOR = 0x07A,
00082  PHIDID_ACCELEROMETER_2AXIS = 0x071,
00083  PHIDID_INTERFACEKIT_0_8_8_w_LCD = 0x053,
00084  PHIDID_INTERFACEKIT_4_8_8 = 4,
00085  PHIDID_LED_64 = 0x04A,
00086  PHIDID_MOTORCONTROL_LV_2MOTOR_4INPUT = 0x058,
00087  PHIDID_PHSENSOR = 0x074,
00088  PHIDID_RFID = 0x030,
00089  PHIDID_SERVO_1MOTOR = 0x039,
00090  PHIDID_SERVO_1MOTOR_OLD = 2,
00091  PHIDID_SERVO_4MOTOR = 0x038,
00092  PHIDID_SERVO_4MOTOR_OLD = 3,
00093  PHIDID_TEXTLCD_2x20 = 0x052,
00094  PHIDID_TEXTLCD_2x20_w_0_8_8 = 0x153,
00095  PHIDID_TEXTLED_1x8 = 0x049,
00096  PHIDID_TEXTLED_4x8 = 0x048,
00097  PHIDID_WEIGHTSENSOR = 0x072,
00098  PHIDID_FIRMWARE_UPGRADE = 0x098,
00099 } CPhidget_DeviceID;
00100 typedef enum {
00101  PHIDUID_NOTHING =1,
00102  PHIDUID_ACCELEROMETER_2AXIS_2G,
00103  PHIDUID_ACCELEROMETER_2AXIS_10G,
00104  PHIDUID_ACCELEROMETER_2AXIS_5G,
00105  PHIDUID_ACCELEROMETER_3AXIS_3G,
00106  PHIDUID_ADVANCEDSERVO_1MOTOR,
00107  PHIDUID_ADVANCEDSERVO_8MOTOR,
00108  PHIDUID_ADVANCEDSERVO_8MOTOR_PGOOD_FLAG,
00109  PHIDUID_ADVANCEDSERVO_8MOTOR_CURSENSE_FIX,
00110  PHIDUID_ANALOG_4OUTPUT,
00111  PHIDUID_BRIDGE_4INPUT,
00112  PHIDUID_ENCODER_1ENCODER_1INPUT_OLD,
00113  PHIDUID_ENCODER_1ENCODER_1INPUT_v1,
00114  PHIDUID_ENCODER_1ENCODER_1INPUT_v2,
00115  PHIDUID_ENCODER_HS_1ENCODER,
00116  PHIDUID_ENCODER_HS_4ENCODER_4INPUT,
00117  PHIDUID_FREQUENCYCOUNTER_2INPUT,
00118  PHIDUID_GPS,
00119  PHIDUID_INTERFACEKIT_0_0_4_NO_ECHO,
00120  PHIDUID_INTERFACEKIT_0_0_4,
00121  PHIDUID_INTERFACEKIT_0_0_8,
00122  PHIDUID_INTERFACEKIT_0_5_7,
00123  PHIDUID_INTERFACEKIT_0_8_8_w_LCD,
00124  PHIDUID_INTERFACEKIT_0_16_16_NO_ECHO,
00125  PHIDUID_INTERFACEKIT_0_16_16_BITBUG,
00126  PHIDUID_INTERFACEKIT_0_16_16,
00127  PHIDUID_INTERFACEKIT_2_2_2,
00128  PHIDUID_INTERFACEKIT_2_8_8,
00129  PHIDUID_INTERFACEKIT_4_8_8,
00130  PHIDUID_INTERFACEKIT_8_8_8_NO_ECHO,
00131  PHIDUID_INTERFACEKIT_8_8_8,
00132  PHIDUID_INTERFACEKIT_8_8_8_FAST,
00133  PHIDUID_INTERFACEKIT_8_8_8_w_LCD_NO_ECHO,
00134  PHIDUID_INTERFACEKIT_8_8_8_w_LCD,
00135  PHIDUID_INTERFACEKIT_8_8_8_w_LCD_FAST,
00136  PHIDUID_INTERFACEKIT_TOUCH_SLIDER,
00137  PHIDUID_INTERFACEKIT_TOUCH_ROTARY,
00138  PHIDUID_IR,
00139  PHIDUID_LED_64,
00140  PHIDUID_LED_64_ADV,
00141  PHIDUID_MOTORCONTROL_1MOTOR,
00142  PHIDUID_MOTORCONTROL_HC_2MOTOR,
00143  PHIDUID_MOTORCONTROL_LV_2MOTOR_4INPUT,
00144  PHIDUID_PHSENSOR,
00145  PHIDUID_RFID_OLD,
00146  PHIDUID_RFID,
00147  PHIDUID_RFID_2OUTPUT_NO_ECHO,
00148  PHIDUID_RFID_2OUTPUT,
00149  PHIDUID_RFID_2OUTPUT_ADVANCED,
00150  PHIDUID_SERVO_1MOTOR_OLD,
00151  PHIDUID_SERVO_4MOTOR_OLD,
00152  PHIDUID_SERVO_1MOTOR_NO_ECHO,
00153  PHIDUID_SERVO_1MOTOR,
00154  PHIDUID_SERVO_4MOTOR_NO_ECHO,
00155  PHIDUID_SERVO_4MOTOR,
00156  PHIDUID_SPATIAL_ACCEL_3AXIS_1049,
00157  PHIDUID_SPATIAL_ACCEL_3AXIS_1041,
00158  PHIDUID_SPATIAL_ACCEL_3AXIS_1043,
00159  PHIDUID_SPATIAL_ACCEL_GYRO_COMPASS_1056,
00160  PHIDUID_SPATIAL_ACCEL_GYRO_COMPASS_1056_NEG_GAIN,
00161  PHIDUID_SPATIAL_ACCEL_GYRO_COMPASS_1042,
00162  PHIDUID_SPATIAL_ACCEL_GYRO_COMPASS_1044,
00163  PHIDUID_STEPPER_BIPOLAR_1MOTOR,
00164  PHIDUID_STEPPER_UNIPOLAR_4MOTOR,
00165  PHIDUID_TEMPERATURESENSOR_OLD,
00166  PHIDUID_TEMPERATURESENSOR,
00167  PHIDUID_TEMPERATURESENSOR_AD22100,
00168  PHIDUID_TEMPERATURESENSOR_TERMINAL_BLOCKS,
00169  PHIDUID_TEMPERATURESENSOR_4,
00170  PHIDUID_TEMPERATURESENSOR_IR,
00171  PHIDUID_TEXTLCD_2x20,
00172  PHIDUID_TEXTLCD_2x20_w_8_8_8,
00173  PHIDUID_TEXTLCD_2x20_w_8_8_8_BRIGHTNESS,
00174  PHIDUID_TEXTLCD_ADAPTER,
00175  PHIDUID_TEXTLED_1x8,
00176  PHIDUID_TEXTLED_4x8,
00177  PHIDUID_WEIGHTSENSOR,
00178  PHIDUID_GENERIC,
00179  PHIDUID_FIRMWARE_UPGRADE
00180 } CPhidget_DeviceUID;
00181  int CPhidget_open(CPhidgetHandle phid, int serialNumber);
00182  int CPhidget_openLabel(CPhidgetHandle phid, const char *label);
00183  int CPhidget_close(CPhidgetHandle phid);
00184  int CPhidget_delete(CPhidgetHandle phid);
00185  int CPhidget_set_OnDetach_Handler(CPhidgetHandle phid, int( *fptr)(CPhidgetHandle phid, void *userPtr), void *userPtr);
00186  int CPhidget_set_OnAttach_Handler(CPhidgetHandle phid, int( *fptr)(CPhidgetHandle phid, void *userPtr), void *userPtr);
00187  int CPhidget_set_OnServerConnect_Handler(CPhidgetHandle phid, int ( *fptr)(CPhidgetHandle phid, void *userPtr), void *userPtr);
00188  int CPhidget_set_OnServerDisconnect_Handler(CPhidgetHandle phid, int ( *fptr)(CPhidgetHandle phid, void *userPtr), void *userPtr);
00189  int CPhidget_set_OnError_Handler(CPhidgetHandle phid, int( *fptr)(CPhidgetHandle phid, void *userPtr, int errorCode, const char *errorString), void *userPtr);
00190  int CPhidget_getDeviceName(CPhidgetHandle phid, const char **deviceName);
00191  int CPhidget_getSerialNumber(CPhidgetHandle phid, int *serialNumber);
00192  int CPhidget_getDeviceVersion(CPhidgetHandle phid, int *deviceVersion);
00193  int CPhidget_getDeviceStatus(CPhidgetHandle phid, int *deviceStatus);
00194  int CPhidget_getLibraryVersion(const char **libraryVersion);
00195  int CPhidget_getDeviceType(CPhidgetHandle phid, const char **deviceType);
00196  int CPhidget_getDeviceLabel(CPhidgetHandle phid, const char **deviceLabel);
00197  int CPhidget_setDeviceLabel(CPhidgetHandle phid, const char *deviceLabel);
00198  int CPhidget_getErrorDescription(int errorCode, const char **errorString);
00199  int CPhidget_waitForAttachment(CPhidgetHandle phid, int milliseconds);
00200  int CPhidget_getServerID(CPhidgetHandle phid, const char **serverID);
00201  int CPhidget_getServerAddress(CPhidgetHandle phid, const char **address, int *port);
00202  int CPhidget_getServerStatus(CPhidgetHandle phid, int *serverStatus);
00203  int CPhidget_getDeviceID(CPhidgetHandle phid, CPhidget_DeviceID *deviceID);
00204  int CPhidget_getDeviceClass(CPhidgetHandle phid, CPhidget_DeviceClass *deviceClass);
00205 typedef enum {
00206  PHIDGET_DICTIONARY_VALUE_CHANGED = 1,
00207  PHIDGET_DICTIONARY_ENTRY_ADDED,
00208  PHIDGET_DICTIONARY_ENTRY_REMOVING,
00209  PHIDGET_DICTIONARY_CURRENT_VALUE
00210 } CPhidgetDictionary_keyChangeReason;
00211 typedef struct _CPhidgetDictionary *CPhidgetDictionaryHandle;
00212 typedef struct _CPhidgetDictionaryListener *CPhidgetDictionaryListenerHandle;
00213  int CPhidgetDictionary_create(CPhidgetDictionaryHandle *dict);
00214  int CPhidgetDictionary_close(CPhidgetDictionaryHandle dict);
00215  int CPhidgetDictionary_delete(CPhidgetDictionaryHandle dict);
00216  int CPhidgetDictionary_set_OnError_Handler(CPhidgetDictionaryHandle dict,
00217     int( *fptr)(CPhidgetDictionaryHandle, void *userPtr, int errorCode, const char *errorString), void *userPtr);
00218  int CPhidgetDictionary_addKey(CPhidgetDictionaryHandle dict, const char *key, const char *value, int persistent);
00219  int CPhidgetDictionary_removeKey(CPhidgetDictionaryHandle dict, const char *pattern);
00220 typedef int( *CPhidgetDictionary_OnKeyChange_Function)(CPhidgetDictionaryHandle dict, void *userPtr,
00221  const char *key, const char *value, CPhidgetDictionary_keyChangeReason reason);
00222  int CPhidgetDictionary_set_OnKeyChange_Handler(CPhidgetDictionaryHandle dict, CPhidgetDictionaryListenerHandle *dictlistener, const char *pattern,
00223  CPhidgetDictionary_OnKeyChange_Function fptr, void *userPtr);
00224  int CPhidgetDictionary_remove_OnKeyChange_Handler(CPhidgetDictionaryListenerHandle dictlistener);
00225  int CPhidgetDictionary_getKey(CPhidgetDictionaryHandle dict, const char *key, char *value, int valuelen);
00226  int CPhidgetDictionary_set_OnServerConnect_Handler(CPhidgetDictionaryHandle dict, int ( *fptr)(CPhidgetDictionaryHandle dict, void *userPtr), void *userPtr);
00227  int CPhidgetDictionary_set_OnServerDisconnect_Handler(CPhidgetDictionaryHandle dict, int ( *fptr)(CPhidgetDictionaryHandle dict, void *userPtr), void *userPtr);
00228  int CPhidgetDictionary_getServerID(CPhidgetDictionaryHandle dict, const char **serverID);
00229  int CPhidgetDictionary_getServerAddress(CPhidgetDictionaryHandle dict, const char **address, int *port);
00230  int CPhidgetDictionary_getServerStatus(CPhidgetDictionaryHandle dict, int *serverStatus);
00231 typedef struct _CPhidgetManager *CPhidgetManagerHandle;
00232  int CPhidgetManager_create(CPhidgetManagerHandle *phidm);
00233  int CPhidgetManager_open(CPhidgetManagerHandle phidm);
00234  int CPhidgetManager_close(CPhidgetManagerHandle phidm);
00235  int CPhidgetManager_delete(CPhidgetManagerHandle phidm);
00236  int CPhidgetManager_set_OnAttach_Handler(CPhidgetManagerHandle phidm, int ( *fptr)(CPhidgetHandle phid, void *userPtr), void *userPtr);
00237  int CPhidgetManager_set_OnDetach_Handler(CPhidgetManagerHandle phidm, int ( *fptr)(CPhidgetHandle phid, void *userPtr), void *userPtr);
00238  int CPhidgetManager_getAttachedDevices(CPhidgetManagerHandle phidm, CPhidgetHandle *phidArray[], int *count);
00239  int CPhidgetManager_freeAttachedDevicesArray(CPhidgetHandle phidArray[]);
00240  int CPhidgetManager_set_OnError_Handler(CPhidgetManagerHandle phidm, int( *fptr)(CPhidgetManagerHandle phidm, void *userPtr, int errorCode, const char *errorString), void *userPtr);
00241  int CPhidgetManager_set_OnServerConnect_Handler(CPhidgetManagerHandle phidm, int ( *fptr)(CPhidgetManagerHandle phidm, void *userPtr), void *userPtr);
00242  int CPhidgetManager_set_OnServerDisconnect_Handler(CPhidgetManagerHandle phidm, int ( *fptr)(CPhidgetManagerHandle phidm, void *userPtr), void *userPtr);
00243  int CPhidgetManager_getServerID(CPhidgetManagerHandle phidm, const char **serverID);
00244  int CPhidgetManager_getServerAddress(CPhidgetManagerHandle phidm, const char **address, int *port);
00245  int CPhidgetManager_getServerStatus(CPhidgetManagerHandle phidm, int *serverStatus);
00246  int CPhidget_openRemote(CPhidgetHandle phid, int serial, const char *serverID, const char *password);
00247  int CPhidget_openLabelRemote(CPhidgetHandle phid, const char *label, const char *serverID, const char *password);
00248  int CPhidget_openRemoteIP(CPhidgetHandle phid, int serial, const char *address, int port, const char *password);
00249  int CPhidget_openLabelRemoteIP(CPhidgetHandle phid, const char *label, const char *address, int port, const char *password);
00250  int CPhidgetManager_openRemote(CPhidgetManagerHandle phidm, const char *serverID, const char *password);
00251  int CPhidgetManager_openRemoteIP(CPhidgetManagerHandle phidm, const char *address, int port, const char *password);
00252  int CPhidgetDictionary_openRemote(CPhidgetDictionaryHandle dict, const char *serverID, const char *password);
00253  int CPhidgetDictionary_openRemoteIP(CPhidgetDictionaryHandle dict, const char *address, int port, const char *password);
00254 typedef enum {
00255  PHIDGET_LOG_CRITICAL = 1,
00256  PHIDGET_LOG_ERROR,
00257  PHIDGET_LOG_WARNING,
00258  PHIDGET_LOG_DEBUG,
00259  PHIDGET_LOG_INFO,
00260  PHIDGET_LOG_VERBOSE
00261 } CPhidgetLog_level;
00262  int CPhidget_enableLogging(CPhidgetLog_level level, const char *outputFile);
00263  int CPhidget_disableLogging();
00264  int CPhidget_log(CPhidgetLog_level level, const char *id, const char *message, ...);
00265 typedef struct _CPhidgetAccelerometer *CPhidgetAccelerometerHandle;
00266  int CPhidgetAccelerometer_create(CPhidgetAccelerometerHandle *phid);
00267  int CPhidgetAccelerometer_getAxisCount(CPhidgetAccelerometerHandle phid, int *count);
00268  int CPhidgetAccelerometer_getAcceleration(CPhidgetAccelerometerHandle phid, int index, double *acceleration);
00269  int CPhidgetAccelerometer_getAccelerationMax(CPhidgetAccelerometerHandle phid, int index, double *max);
00270  int CPhidgetAccelerometer_getAccelerationMin(CPhidgetAccelerometerHandle phid, int index, double *min);
00271  int CPhidgetAccelerometer_set_OnAccelerationChange_Handler(CPhidgetAccelerometerHandle phid, int ( *fptr)(CPhidgetAccelerometerHandle phid, void *userPtr, int index, double acceleration), void *userPtr);
00272  int CPhidgetAccelerometer_getAccelerationChangeTrigger(CPhidgetAccelerometerHandle phid, int index, double *trigger);
00273  int CPhidgetAccelerometer_setAccelerationChangeTrigger(CPhidgetAccelerometerHandle phid, int index, double trigger);
00274 typedef struct _CPhidgetAdvancedServo *CPhidgetAdvancedServoHandle;
00275  int CPhidgetAdvancedServo_create(CPhidgetAdvancedServoHandle *phid);
00276 typedef enum {
00277  PHIDGET_SERVO_DEFAULT = 1,
00278  PHIDGET_SERVO_RAW_us_MODE,
00279  PHIDGET_SERVO_HITEC_HS322HD,
00280  PHIDGET_SERVO_HITEC_HS5245MG,
00281  PHIDGET_SERVO_HITEC_805BB,
00282  PHIDGET_SERVO_HITEC_HS422,
00283  PHIDGET_SERVO_TOWERPRO_MG90,
00284  PHIDGET_SERVO_HITEC_HSR1425CR,
00285  PHIDGET_SERVO_HITEC_HS785HB,
00286  PHIDGET_SERVO_HITEC_HS485HB,
00287  PHIDGET_SERVO_HITEC_HS645MG,
00288  PHIDGET_SERVO_HITEC_815BB,
00289  PHIDGET_SERVO_FIRGELLI_L12_30_50_06_R,
00290  PHIDGET_SERVO_FIRGELLI_L12_50_100_06_R,
00291  PHIDGET_SERVO_FIRGELLI_L12_50_210_06_R,
00292  PHIDGET_SERVO_FIRGELLI_L12_100_50_06_R,
00293  PHIDGET_SERVO_FIRGELLI_L12_100_100_06_R,
00294  PHIDGET_SERVO_SPRINGRC_SM_S2313M,
00295  PHIDGET_SERVO_SPRINGRC_SM_S3317M,
00296  PHIDGET_SERVO_SPRINGRC_SM_S3317SR,
00297  PHIDGET_SERVO_SPRINGRC_SM_S4303R,
00298  PHIDGET_SERVO_SPRINGRC_SM_S4315M,
00299  PHIDGET_SERVO_SPRINGRC_SM_S4315R,
00300  PHIDGET_SERVO_SPRINGRC_SM_S4505B,
00301  PHIDGET_SERVO_USER_DEFINED
00302 } CPhidget_ServoType;
00303  int CPhidgetAdvancedServo_getMotorCount(CPhidgetAdvancedServoHandle phid, int *count);
00304  int CPhidgetAdvancedServo_getAcceleration(CPhidgetAdvancedServoHandle phid, int index, double *acceleration);
00305  int CPhidgetAdvancedServo_setAcceleration(CPhidgetAdvancedServoHandle phid, int index, double acceleration);
00306  int CPhidgetAdvancedServo_getAccelerationMax(CPhidgetAdvancedServoHandle phid, int index, double *max);
00307  int CPhidgetAdvancedServo_getAccelerationMin(CPhidgetAdvancedServoHandle phid, int index, double *min);
00308  int CPhidgetAdvancedServo_getVelocityLimit(CPhidgetAdvancedServoHandle phid, int index, double *limit);
00309  int CPhidgetAdvancedServo_setVelocityLimit(CPhidgetAdvancedServoHandle phid, int index, double limit);
00310  int CPhidgetAdvancedServo_getVelocity(CPhidgetAdvancedServoHandle phid, int index, double *velocity);
00311  int CPhidgetAdvancedServo_getVelocityMax(CPhidgetAdvancedServoHandle phid, int index, double *max);
00312  int CPhidgetAdvancedServo_getVelocityMin(CPhidgetAdvancedServoHandle phid, int index, double *min);
00313  int CPhidgetAdvancedServo_set_OnVelocityChange_Handler(CPhidgetAdvancedServoHandle phid, int ( *fptr)(CPhidgetAdvancedServoHandle phid, void *userPtr, int index, double velocity), void *userPtr);
00314  int CPhidgetAdvancedServo_getPosition(CPhidgetAdvancedServoHandle phid, int index, double *position);
00315  int CPhidgetAdvancedServo_setPosition(CPhidgetAdvancedServoHandle phid, int index, double position);
00316  int CPhidgetAdvancedServo_getPositionMax(CPhidgetAdvancedServoHandle phid, int index, double *max);
00317  int CPhidgetAdvancedServo_setPositionMax(CPhidgetAdvancedServoHandle phid, int index, double max);
00318  int CPhidgetAdvancedServo_getPositionMin(CPhidgetAdvancedServoHandle phid, int index, double *min);
00319  int CPhidgetAdvancedServo_setPositionMin(CPhidgetAdvancedServoHandle phid, int index, double min);
00320  int CPhidgetAdvancedServo_set_OnPositionChange_Handler(CPhidgetAdvancedServoHandle phid, int ( *fptr)(CPhidgetAdvancedServoHandle phid, void *userPtr, int index, double position), void *userPtr);
00321  int CPhidgetAdvancedServo_getCurrent(CPhidgetAdvancedServoHandle phid, int index, double *current);
00322  int CPhidgetAdvancedServo_set_OnCurrentChange_Handler(CPhidgetAdvancedServoHandle phid, int ( *fptr)(CPhidgetAdvancedServoHandle phid, void *userPtr, int index, double current), void *userPtr);
00323  int CPhidgetAdvancedServo_getSpeedRampingOn(CPhidgetAdvancedServoHandle phid, int index, int *rampingState);
00324  int CPhidgetAdvancedServo_setSpeedRampingOn(CPhidgetAdvancedServoHandle phid, int index, int rampingState);
00325  int CPhidgetAdvancedServo_getEngaged(CPhidgetAdvancedServoHandle phid, int index, int *engagedState);
00326  int CPhidgetAdvancedServo_setEngaged(CPhidgetAdvancedServoHandle phid, int index, int engagedState);
00327  int CPhidgetAdvancedServo_getStopped(CPhidgetAdvancedServoHandle phid, int index, int *stoppedState);
00328  int CPhidgetAdvancedServo_getServoType(CPhidgetAdvancedServoHandle phid, int index, CPhidget_ServoType *servoType);
00329  int CPhidgetAdvancedServo_setServoType(CPhidgetAdvancedServoHandle phid, int index, CPhidget_ServoType servoType);
00330  int CPhidgetAdvancedServo_setServoParameters(CPhidgetAdvancedServoHandle phid, int index, double min_us,double max_us,double degrees,double velocity_max);
00331 typedef struct _CPhidgetAnalog *CPhidgetAnalogHandle;
00332  int CPhidgetAnalog_create(CPhidgetAnalogHandle *phid);
00333  int CPhidgetAnalog_getOutputCount(CPhidgetAnalogHandle phid, int *count);
00334  int CPhidgetAnalog_getVoltage(CPhidgetAnalogHandle phid, int index, double *voltage);
00335  int CPhidgetAnalog_setVoltage(CPhidgetAnalogHandle phid, int index, double voltage);
00336  int CPhidgetAnalog_getVoltageMax(CPhidgetAnalogHandle phid, int index, double *max);
00337  int CPhidgetAnalog_getVoltageMin(CPhidgetAnalogHandle phid, int index, double *min);
00338  int CPhidgetAnalog_setEnabled(CPhidgetAnalogHandle phid, int index, int enabledState);
00339  int CPhidgetAnalog_getEnabled(CPhidgetAnalogHandle phid, int index, int *enabledState);
00340 typedef enum {
00341  PHIDGET_BRIDGE_GAIN_1 = 1,
00342  PHIDGET_BRIDGE_GAIN_8,
00343  PHIDGET_BRIDGE_GAIN_16,
00344  PHIDGET_BRIDGE_GAIN_32,
00345  PHIDGET_BRIDGE_GAIN_64,
00346  PHIDGET_BRIDGE_GAIN_128,
00347  PHIDGET_BRIDGE_GAIN_UNKNOWN
00348 } CPhidgetBridge_Gain;
00349 typedef struct _CPhidgetBridge *CPhidgetBridgeHandle;
00350  int CPhidgetBridge_create(CPhidgetBridgeHandle *phid);
00351  int CPhidgetBridge_getInputCount(CPhidgetBridgeHandle phid, int *count);
00352  int CPhidgetBridge_getBridgeValue(CPhidgetBridgeHandle phid, int index, double *value);
00353  int CPhidgetBridge_getBridgeMax(CPhidgetBridgeHandle phid, int index, double *max);
00354  int CPhidgetBridge_getBridgeMin(CPhidgetBridgeHandle phid, int index, double *min);
00355  int CPhidgetBridge_setEnabled(CPhidgetBridgeHandle phid, int index, int enabledState);
00356  int CPhidgetBridge_getEnabled(CPhidgetBridgeHandle phid, int index, int *enabledState);
00357  int CPhidgetBridge_getGain(CPhidgetBridgeHandle phid, int index, CPhidgetBridge_Gain *gain);
00358  int CPhidgetBridge_setGain(CPhidgetBridgeHandle phid, int index, CPhidgetBridge_Gain gain);
00359  int CPhidgetBridge_getDataRate(CPhidgetBridgeHandle phid, int *milliseconds);
00360  int CPhidgetBridge_setDataRate(CPhidgetBridgeHandle phid, int milliseconds);
00361  int CPhidgetBridge_getDataRateMax(CPhidgetBridgeHandle phid, int *max);
00362  int CPhidgetBridge_getDataRateMin(CPhidgetBridgeHandle phid, int *min);
00363  int CPhidgetBridge_set_OnBridgeData_Handler(CPhidgetBridgeHandle phid, int ( *fptr)(CPhidgetBridgeHandle phid, void *userPtr, int index, double value), void *userPtr);
00364 typedef struct _CPhidgetEncoder *CPhidgetEncoderHandle;
00365  int CPhidgetEncoder_create(CPhidgetEncoderHandle *phid);
00366  int CPhidgetEncoder_getInputCount(CPhidgetEncoderHandle phid, int *count);
00367  int CPhidgetEncoder_getInputState(CPhidgetEncoderHandle phid, int index, int *inputState);
00368  int CPhidgetEncoder_set_OnInputChange_Handler(CPhidgetEncoderHandle phid, int ( *fptr)(CPhidgetEncoderHandle phid, void *userPtr, int index, int inputState), void *userPtr);
00369  int CPhidgetEncoder_getEncoderCount(CPhidgetEncoderHandle phid, int *count);
00370  int CPhidgetEncoder_getPosition(CPhidgetEncoderHandle phid, int index, int *position);
00371  int CPhidgetEncoder_setPosition(CPhidgetEncoderHandle phid, int index, int position);
00372  int CPhidgetEncoder_set_OnPositionChange_Handler(CPhidgetEncoderHandle phid, int ( *fptr)(CPhidgetEncoderHandle phid, void *userPtr, int index, int time,int positionChange), void *userPtr);
00373  int CPhidgetEncoder_set_OnIndexChange_Handler(CPhidgetEncoderHandle phid, int ( *fptr)(CPhidgetEncoderHandle phid, void *userPtr, int index, int indexPosition), void *userPtr);
00374  int CPhidgetEncoder_getIndexPosition(CPhidgetEncoderHandle phid, int index, int *position);
00375  int CPhidgetEncoder_getEnabled(CPhidgetEncoderHandle phid, int index, int *enabledState);
00376  int CPhidgetEncoder_setEnabled(CPhidgetEncoderHandle phid, int index, int enabledState);
00377 typedef enum {
00378  PHIDGET_FREQUENCYCOUNTER_FILTERTYPE_ZERO_CROSSING = 1,
00379  PHIDGET_FREQUENCYCOUNTER_FILTERTYPE_LOGIC_LEVEL,
00380  PHIDGET_FREQUENCYCOUNTER_FILTERTYPE_UNKNOWN
00381 } CPhidgetFrequencyCounter_FilterType;
00382 typedef struct _CPhidgetFrequencyCounter *CPhidgetFrequencyCounterHandle;
00383  int CPhidgetFrequencyCounter_create(CPhidgetFrequencyCounterHandle *phid);
00384  int CPhidgetFrequencyCounter_getFrequencyInputCount(CPhidgetFrequencyCounterHandle phid, int *count);
00385  int CPhidgetFrequencyCounter_getFrequency(CPhidgetFrequencyCounterHandle phid, int index, double *frequency);
00386  int CPhidgetFrequencyCounter_getTotalTime(CPhidgetFrequencyCounterHandle phid, int index, __int64 *time);
00387  int CPhidgetFrequencyCounter_getTotalCount(CPhidgetFrequencyCounterHandle phid, int index, __int64 *count);
00388  int CPhidgetFrequencyCounter_setTimeout(CPhidgetFrequencyCounterHandle phid, int index, int timeout);
00389  int CPhidgetFrequencyCounter_getTimeout(CPhidgetFrequencyCounterHandle phid, int index, int *timeout);
00390  int CPhidgetFrequencyCounter_setEnabled(CPhidgetFrequencyCounterHandle phid, int index, int enabledState);
00391  int CPhidgetFrequencyCounter_getEnabled(CPhidgetFrequencyCounterHandle phid, int index, int *enabledState);
00392  int CPhidgetFrequencyCounter_setFilter(CPhidgetFrequencyCounterHandle phid, int index, CPhidgetFrequencyCounter_FilterType filter);
00393  int CPhidgetFrequencyCounter_getFilter(CPhidgetFrequencyCounterHandle phid, int index, CPhidgetFrequencyCounter_FilterType *filter);
00394  int CPhidgetFrequencyCounter_reset(CPhidgetFrequencyCounterHandle phid, int index);
00395  int CPhidgetFrequencyCounter_set_OnCount_Handler(CPhidgetFrequencyCounterHandle phid, int ( *fptr)(CPhidgetFrequencyCounterHandle phid, void *userPtr, int index, int time,int counts), void *userPtr);
00396 struct __GPSTime
00397 {
00398  short tm_ms;
00399  short tm_sec;
00400  short tm_min;
00401  short tm_hour;
00402 } typedef GPSTime;
00403 struct __GPSDate
00404 {
00405  short tm_mday;
00406  short tm_mon;
00407  short tm_year;
00408 } typedef GPSDate;
00409 struct __GPSSatInfo
00410 {
00411  short ID;
00412  short elevation;
00413  int azimuth;
00414  short SNR;
00415 } typedef GPSSatInfo;
00416 struct __GPGGA
00417 {
00418  GPSTime time;
00419  double latitude;
00420  double longitude;
00421  short fixQuality;
00422  short numSatellites;
00423  double horizontalDilution;
00424  double altitude;
00425  double heightOfGeoid;
00426 } typedef GPGGA;
00427 struct __GPGSA
00428 {
00429  char mode;
00430  short fixType;
00431  short satUsed[12];
00432  double posnDilution;
00433  double horizDilution;
00434  double vertDilution;
00435 } typedef GPGSA;
00436 struct __GPGSV
00437 {
00438  short satsInView;
00439  GPSSatInfo satInfo[12];
00440 } typedef GPGSV;
00441 struct __GPRMC
00442 {
00443  GPSTime time;
00444  char status;
00445  double latitude;
00446  double longitude;
00447  double speedKnots;
00448  double heading;
00449  GPSDate date;
00450  double magneticVariation;
00451  char mode;
00452 } typedef GPRMC;
00453 struct __GPVTG
00454 {
00455  double trueHeading;
00456  double magneticHeading;
00457  double speedKnots;
00458  double speed;
00459  char mode;
00460 } typedef GPVTG;
00461 struct __NMEAData
00462 {
00463  GPGGA GGA;
00464  GPGSA GSA;
00465  GPGSV GSV;
00466  GPRMC RMC;
00467  GPVTG VTG;
00468 } typedef NMEAData;
00469 typedef struct _CPhidgetGPS *CPhidgetGPSHandle;
00470  int CPhidgetGPS_create(CPhidgetGPSHandle *phid);
00471  int CPhidgetGPS_getLatitude(CPhidgetGPSHandle phid, double *latitude);
00472  int CPhidgetGPS_getLongitude(CPhidgetGPSHandle phid, double *longitude);
00473  int CPhidgetGPS_getAltitude(CPhidgetGPSHandle phid, double *altitude);
00474  int CPhidgetGPS_getHeading(CPhidgetGPSHandle phid, double *heading);
00475  int CPhidgetGPS_getVelocity(CPhidgetGPSHandle phid, double *velocity);
00476  int CPhidgetGPS_getTime(CPhidgetGPSHandle phid, GPSTime *time);
00477  int CPhidgetGPS_getDate(CPhidgetGPSHandle phid, GPSDate *date);
00478  int CPhidgetGPS_getPositionFixStatus(CPhidgetGPSHandle phid, int *fixStatus);
00479  int CPhidgetGPS_getNMEAData(CPhidgetGPSHandle phid, NMEAData *data);
00480  int CPhidgetGPS_set_OnPositionChange_Handler(CPhidgetGPSHandle phid, int ( *fptr)(CPhidgetGPSHandle phid, void *userPtr, double latitude,double longitude,double altitude), void *userPtr);
00481  int CPhidgetGPS_set_OnPositionFixStatusChange_Handler(CPhidgetGPSHandle phid, int ( *fptr)(CPhidgetGPSHandle phid, void *userPtr, int status), void *userPtr);
00482 typedef struct _CPhidgetInterfaceKit *CPhidgetInterfaceKitHandle;
00483  int CPhidgetInterfaceKit_create(CPhidgetInterfaceKitHandle *phid);
00484  int CPhidgetInterfaceKit_getInputCount(CPhidgetInterfaceKitHandle phid, int *count);
00485  int CPhidgetInterfaceKit_getInputState(CPhidgetInterfaceKitHandle phid, int index, int *inputState);
00486  int CPhidgetInterfaceKit_set_OnInputChange_Handler(CPhidgetInterfaceKitHandle phid, int ( *fptr)(CPhidgetInterfaceKitHandle phid, void *userPtr, int index, int inputState), void *userPtr);
00487  int CPhidgetInterfaceKit_getOutputCount(CPhidgetInterfaceKitHandle phid, int *count);
00488  int CPhidgetInterfaceKit_getOutputState(CPhidgetInterfaceKitHandle phid, int index, int *outputState);
00489  int CPhidgetInterfaceKit_setOutputState(CPhidgetInterfaceKitHandle phid, int index, int outputState);
00490  int CPhidgetInterfaceKit_set_OnOutputChange_Handler(CPhidgetInterfaceKitHandle phid, int ( *fptr)(CPhidgetInterfaceKitHandle phid, void *userPtr, int index, int outputState), void *userPtr);
00491  int CPhidgetInterfaceKit_getSensorCount(CPhidgetInterfaceKitHandle phid, int *count);
00492  int CPhidgetInterfaceKit_getSensorValue(CPhidgetInterfaceKitHandle phid, int index, int *sensorValue);
00493  int CPhidgetInterfaceKit_getSensorRawValue(CPhidgetInterfaceKitHandle phid, int index, int *sensorRawValue);
00494  int CPhidgetInterfaceKit_set_OnSensorChange_Handler(CPhidgetInterfaceKitHandle phid, int ( *fptr)(CPhidgetInterfaceKitHandle phid, void *userPtr, int index, int sensorValue), void *userPtr);
00495  int CPhidgetInterfaceKit_getSensorChangeTrigger(CPhidgetInterfaceKitHandle phid, int index, int *trigger);
00496  int CPhidgetInterfaceKit_setSensorChangeTrigger(CPhidgetInterfaceKitHandle phid, int index, int trigger);
00497  int CPhidgetInterfaceKit_getRatiometric(CPhidgetInterfaceKitHandle phid, int *ratiometric);
00498  int CPhidgetInterfaceKit_setRatiometric(CPhidgetInterfaceKitHandle phid, int ratiometric);
00499  int CPhidgetInterfaceKit_getDataRate(CPhidgetInterfaceKitHandle phid, int index, int *milliseconds);
00500  int CPhidgetInterfaceKit_setDataRate(CPhidgetInterfaceKitHandle phid, int index, int milliseconds);
00501  int CPhidgetInterfaceKit_getDataRateMax(CPhidgetInterfaceKitHandle phid, int index, int *max);
00502  int CPhidgetInterfaceKit_getDataRateMin(CPhidgetInterfaceKitHandle phid, int index, int *min);
00503 typedef struct _CPhidgetIR *CPhidgetIRHandle;
00504  int CPhidgetIR_create(CPhidgetIRHandle *phid);
00505 typedef enum {
00506  PHIDGET_IR_ENCODING_UNKNOWN = 1,
00507  PHIDGET_IR_ENCODING_SPACE,
00508  PHIDGET_IR_ENCODING_PULSE,
00509  PHIDGET_IR_ENCODING_BIPHASE,
00510  PHIDGET_IR_ENCODING_RC5,
00511  PHIDGET_IR_ENCODING_RC6
00512 } CPhidgetIR_Encoding;
00513 typedef enum {
00514  PHIDGET_IR_LENGTH_UNKNOWN = 1,
00515  PHIDGET_IR_LENGTH_CONSTANT,
00516  PHIDGET_IR_LENGTH_VARIABLE
00517 } CPhidgetIR_Length;
00518 typedef struct _CPhidgetIR_CodeInfo
00519 {
00520  int bitCount;
00521  CPhidgetIR_Encoding encoding;
00522  CPhidgetIR_Length length;
00523  int gap;
00524  int trail;
00525  int header[2];
00526  int one[2];
00527  int zero[2];
00528  int repeat[26];
00529  int min_repeat;
00530  unsigned char toggle_mask[(128 / 8)];
00531  int carrierFrequency;
00532  int dutyCycle;
00533 } CPhidgetIR_CodeInfo, *CPhidgetIR_CodeInfoHandle;
00534  int CPhidgetIR_Transmit(CPhidgetIRHandle phid, unsigned char *data, CPhidgetIR_CodeInfoHandle codeInfo);
00535  int CPhidgetIR_TransmitRepeat(CPhidgetIRHandle phid);
00536  int CPhidgetIR_TransmitRaw(CPhidgetIRHandle phid, int *data, int length, int carrierFrequency, int dutyCycle, int gap);
00537  int CPhidgetIR_getRawData(CPhidgetIRHandle phid, int *data, int *dataLength);
00538  int CPhidgetIR_getLastCode(CPhidgetIRHandle phid, unsigned char *data, int *dataLength, int *bitCount);
00539  int CPhidgetIR_getLastLearnedCode(CPhidgetIRHandle phid, unsigned char *data, int *dataLength, CPhidgetIR_CodeInfo *codeInfo);
00540  int CPhidgetIR_set_OnCode_Handler(CPhidgetIRHandle phid, int ( *fptr)(CPhidgetIRHandle phid, void *userPtr, unsigned char *data, int dataLength, int bitCount, int repeat), void *userPtr);
00541  int CPhidgetIR_set_OnLearn_Handler(CPhidgetIRHandle phid, int ( *fptr)(CPhidgetIRHandle phid, void *userPtr, unsigned char *data, int dataLength, CPhidgetIR_CodeInfoHandle codeInfo), void *userPtr);
00542  int CPhidgetIR_set_OnRawData_Handler(CPhidgetIRHandle phid, int ( *fptr)(CPhidgetIRHandle phid, void *userPtr, int *data, int dataLength), void *userPtr);
00543 typedef struct _CPhidgetLED *CPhidgetLEDHandle;
00544  int CPhidgetLED_create(CPhidgetLEDHandle *phid);
00545 typedef enum {
00546  PHIDGET_LED_CURRENT_LIMIT_20mA = 1,
00547  PHIDGET_LED_CURRENT_LIMIT_40mA,
00548  PHIDGET_LED_CURRENT_LIMIT_60mA,
00549  PHIDGET_LED_CURRENT_LIMIT_80mA
00550 } CPhidgetLED_CurrentLimit;
00551 typedef enum {
00552  PHIDGET_LED_VOLTAGE_1_7V = 1,
00553  PHIDGET_LED_VOLTAGE_2_75V,
00554  PHIDGET_LED_VOLTAGE_3_9V,
00555  PHIDGET_LED_VOLTAGE_5_0V
00556 } CPhidgetLED_Voltage;
00557  int CPhidgetLED_getLEDCount(CPhidgetLEDHandle phid, int *count);
00558  int CPhidgetLED_getDiscreteLED(CPhidgetLEDHandle phid, int index, int *brightness);
00559  int CPhidgetLED_setDiscreteLED(CPhidgetLEDHandle phid, int index, int brightness);
00560  int CPhidgetLED_getCurrentLimit(CPhidgetLEDHandle phid, CPhidgetLED_CurrentLimit *currentLimit);
00561  int CPhidgetLED_setCurrentLimit(CPhidgetLEDHandle phid, CPhidgetLED_CurrentLimit currentLimit);
00562  int CPhidgetLED_getVoltage(CPhidgetLEDHandle phid, CPhidgetLED_Voltage *voltage);
00563  int CPhidgetLED_setVoltage(CPhidgetLEDHandle phid, CPhidgetLED_Voltage voltage);
00564 typedef struct _CPhidgetMotorControl *CPhidgetMotorControlHandle;
00565  int CPhidgetMotorControl_create(CPhidgetMotorControlHandle *phid);
00566  int CPhidgetMotorControl_getMotorCount(CPhidgetMotorControlHandle phid, int *count);
00567  int CPhidgetMotorControl_getVelocity(CPhidgetMotorControlHandle phid, int index, double *velocity);
00568  int CPhidgetMotorControl_setVelocity(CPhidgetMotorControlHandle phid, int index, double velocity);
00569  int CPhidgetMotorControl_set_OnVelocityChange_Handler(CPhidgetMotorControlHandle phid, int ( *fptr)(CPhidgetMotorControlHandle phid, void *userPtr, int index, double velocity), void *userPtr);
00570  int CPhidgetMotorControl_getAcceleration(CPhidgetMotorControlHandle phid, int index, double *acceleration);
00571  int CPhidgetMotorControl_setAcceleration(CPhidgetMotorControlHandle phid, int index, double acceleration);
00572  int CPhidgetMotorControl_getAccelerationMax(CPhidgetMotorControlHandle phid, int index, double *max);
00573  int CPhidgetMotorControl_getAccelerationMin(CPhidgetMotorControlHandle phid, int index, double *min);
00574  int CPhidgetMotorControl_getCurrent(CPhidgetMotorControlHandle phid, int index, double *current);
00575  int CPhidgetMotorControl_set_OnCurrentChange_Handler(CPhidgetMotorControlHandle phid, int ( *fptr)(CPhidgetMotorControlHandle phid, void *userPtr, int index, double current), void *userPtr);
00576  int CPhidgetMotorControl_getInputCount(CPhidgetMotorControlHandle phid, int *count);
00577  int CPhidgetMotorControl_getInputState(CPhidgetMotorControlHandle phid, int index, int *inputState);
00578  int CPhidgetMotorControl_set_OnInputChange_Handler(CPhidgetMotorControlHandle phid, int ( *fptr)(CPhidgetMotorControlHandle phid, void *userPtr, int index, int inputState), void *userPtr);
00579  int CPhidgetMotorControl_getEncoderCount(CPhidgetMotorControlHandle phid, int *count);
00580  int CPhidgetMotorControl_getEncoderPosition(CPhidgetMotorControlHandle phid, int index, int *position);
00581  int CPhidgetMotorControl_setEncoderPosition(CPhidgetMotorControlHandle phid, int index, int position);
00582  int CPhidgetMotorControl_set_OnEncoderPositionChange_Handler(CPhidgetMotorControlHandle phid, int ( *fptr)(CPhidgetMotorControlHandle phid, void *userPtr, int index, int time,int positionChange), void *userPtr);
00583  int CPhidgetMotorControl_set_OnEncoderPositionUpdate_Handler(CPhidgetMotorControlHandle phid, int ( *fptr)(CPhidgetMotorControlHandle phid, void *userPtr, int index, int positionChange), void *userPtr);
00584  int CPhidgetMotorControl_getBackEMFSensingState(CPhidgetMotorControlHandle phid, int index, int *bEMFState);
00585  int CPhidgetMotorControl_setBackEMFSensingState(CPhidgetMotorControlHandle phid, int index, int bEMFState);
00586  int CPhidgetMotorControl_getBackEMF(CPhidgetMotorControlHandle phid, int index, double *voltage);
00587  int CPhidgetMotorControl_set_OnBackEMFUpdate_Handler(CPhidgetMotorControlHandle phid, int ( *fptr)(CPhidgetMotorControlHandle phid, void *userPtr, int index, double voltage), void *userPtr);
00588  int CPhidgetMotorControl_getSupplyVoltage(CPhidgetMotorControlHandle phid, double *supplyVoltage);
00589  int CPhidgetMotorControl_getBraking(CPhidgetMotorControlHandle phid, int index, double *braking);
00590  int CPhidgetMotorControl_setBraking(CPhidgetMotorControlHandle phid, int index, double braking);
00591  int CPhidgetMotorControl_getSensorCount(CPhidgetMotorControlHandle phid, int *count);
00592  int CPhidgetMotorControl_getSensorValue(CPhidgetMotorControlHandle phid, int index, int *sensorValue);
00593  int CPhidgetMotorControl_getSensorRawValue(CPhidgetMotorControlHandle phid, int index, int *sensorRawValue);
00594  int CPhidgetMotorControl_set_OnSensorUpdate_Handler(CPhidgetMotorControlHandle phid, int ( *fptr)(CPhidgetMotorControlHandle phid, void *userPtr, int index, int sensorValue), void *userPtr);
00595  int CPhidgetMotorControl_getRatiometric(CPhidgetMotorControlHandle phid, int *ratiometric);
00596  int CPhidgetMotorControl_setRatiometric(CPhidgetMotorControlHandle phid, int ratiometric);
00597  int CPhidgetMotorControl_set_OnCurrentUpdate_Handler(CPhidgetMotorControlHandle phid, int ( *fptr)(CPhidgetMotorControlHandle phid, void *userPtr, int index, double current), void *userPtr);
00598 typedef struct _CPhidgetPHSensor *CPhidgetPHSensorHandle;
00599  int CPhidgetPHSensor_create(CPhidgetPHSensorHandle *phid);
00600  int CPhidgetPHSensor_getPH(CPhidgetPHSensorHandle phid, double *ph);
00601  int CPhidgetPHSensor_getPHMax(CPhidgetPHSensorHandle phid, double *max);
00602  int CPhidgetPHSensor_getPHMin(CPhidgetPHSensorHandle phid, double *min);
00603  int CPhidgetPHSensor_set_OnPHChange_Handler(CPhidgetPHSensorHandle phid, int ( *fptr)(CPhidgetPHSensorHandle phid, void *userPtr, double ph), void *userPtr);
00604  int CPhidgetPHSensor_getPHChangeTrigger(CPhidgetPHSensorHandle phid, double *trigger);
00605  int CPhidgetPHSensor_setPHChangeTrigger(CPhidgetPHSensorHandle phid, double trigger);
00606  int CPhidgetPHSensor_getPotential(CPhidgetPHSensorHandle phid, double *potential);
00607  int CPhidgetPHSensor_getPotentialMax(CPhidgetPHSensorHandle phid, double *max);
00608  int CPhidgetPHSensor_getPotentialMin(CPhidgetPHSensorHandle phid, double *min);
00609  int CPhidgetPHSensor_setTemperature(CPhidgetPHSensorHandle phid, double temperature);
00610 typedef struct _CPhidgetRFID *CPhidgetRFIDHandle;
00611  int CPhidgetRFID_create(CPhidgetRFIDHandle *phid);
00612  int CPhidgetRFID_getOutputCount(CPhidgetRFIDHandle phid, int *count);
00613  int CPhidgetRFID_getOutputState(CPhidgetRFIDHandle phid, int index, int *outputState);
00614  int CPhidgetRFID_setOutputState(CPhidgetRFIDHandle phid, int index, int outputState);
00615  int CPhidgetRFID_set_OnOutputChange_Handler(CPhidgetRFIDHandle phid, int ( *fptr)(CPhidgetRFIDHandle phid, void *userPtr, int index, int outputState), void *userPtr);
00616  int CPhidgetRFID_getAntennaOn(CPhidgetRFIDHandle phid, int *antennaState);
00617  int CPhidgetRFID_setAntennaOn(CPhidgetRFIDHandle phid, int antennaState);
00618  int CPhidgetRFID_getLEDOn(CPhidgetRFIDHandle phid, int *LEDState);
00619  int CPhidgetRFID_setLEDOn(CPhidgetRFIDHandle phid, int LEDState);
00620  int CPhidgetRFID_getLastTag(CPhidgetRFIDHandle phid, unsigned char *tag);
00621  int CPhidgetRFID_getTagStatus(CPhidgetRFIDHandle phid, int *status);
00622  int CPhidgetRFID_set_OnTag_Handler(CPhidgetRFIDHandle phid, int ( *fptr)(CPhidgetRFIDHandle phid, void *userPtr, unsigned char *tag), void *userPtr);
00623  int CPhidgetRFID_set_OnTagLost_Handler(CPhidgetRFIDHandle phid, int ( *fptr)(CPhidgetRFIDHandle phid, void *userPtr, unsigned char *tag), void *userPtr);
00624 typedef struct _CPhidgetServo *CPhidgetServoHandle;
00625  int CPhidgetServo_create(CPhidgetServoHandle *phid);
00626  int CPhidgetServo_getMotorCount(CPhidgetServoHandle phid, int *count);
00627  int CPhidgetServo_getPosition(CPhidgetServoHandle phid, int index, double *position);
00628  int CPhidgetServo_setPosition(CPhidgetServoHandle phid, int index, double position);
00629  int CPhidgetServo_getPositionMax(CPhidgetServoHandle phid, int index, double *max);
00630  int CPhidgetServo_getPositionMin(CPhidgetServoHandle phid, int index, double *min);
00631  int CPhidgetServo_set_OnPositionChange_Handler(CPhidgetServoHandle phid, int ( *fptr)(CPhidgetServoHandle phid, void *userPtr, int index, double position), void *userPtr);
00632  int CPhidgetServo_getEngaged(CPhidgetServoHandle phid, int index, int *engagedState);
00633  int CPhidgetServo_setEngaged(CPhidgetServoHandle phid, int index, int engagedState);
00634  int CPhidgetServo_getServoType(CPhidgetServoHandle phid, int index, CPhidget_ServoType *servoType);
00635  int CPhidgetServo_setServoType(CPhidgetServoHandle phid, int index, CPhidget_ServoType servoType);
00636  int CPhidgetServo_setServoParameters(CPhidgetServoHandle phid, int index, double min_us,double max_us,double degrees);
00637 typedef struct _CPhidgetSpatial *CPhidgetSpatialHandle;
00638  int CPhidgetSpatial_create(CPhidgetSpatialHandle *phid);
00639 typedef struct _CPhidgetSpatial_SpatialEventData
00640 {
00641  double acceleration[3];
00642  double angularRate[3];
00643  double magneticField[3];
00644  CPhidget_Timestamp timestamp;
00645 } CPhidgetSpatial_SpatialEventData, *CPhidgetSpatial_SpatialEventDataHandle;
00646  int CPhidgetSpatial_getAccelerationAxisCount(CPhidgetSpatialHandle phid, int *count);
00647  int CPhidgetSpatial_getGyroAxisCount(CPhidgetSpatialHandle phid, int *count);
00648  int CPhidgetSpatial_getCompassAxisCount(CPhidgetSpatialHandle phid, int *count);
00649  int CPhidgetSpatial_getAcceleration(CPhidgetSpatialHandle phid, int index, double *acceleration);
00650  int CPhidgetSpatial_getAccelerationMax(CPhidgetSpatialHandle phid, int index, double *max);
00651  int CPhidgetSpatial_getAccelerationMin(CPhidgetSpatialHandle phid, int index, double *min);
00652  int CPhidgetSpatial_getAngularRate(CPhidgetSpatialHandle phid, int index, double *angularRate);
00653  int CPhidgetSpatial_getAngularRateMax(CPhidgetSpatialHandle phid, int index, double *max);
00654  int CPhidgetSpatial_getAngularRateMin(CPhidgetSpatialHandle phid, int index, double *min);
00655  int CPhidgetSpatial_getMagneticField(CPhidgetSpatialHandle phid, int index, double *magneticField);
00656  int CPhidgetSpatial_getMagneticFieldMax(CPhidgetSpatialHandle phid, int index, double *max);
00657  int CPhidgetSpatial_getMagneticFieldMin(CPhidgetSpatialHandle phid, int index, double *min);
00658  int CPhidgetSpatial_zeroGyro(CPhidgetSpatialHandle phid);
00659  int CPhidgetSpatial_getDataRate(CPhidgetSpatialHandle phid, int *milliseconds);
00660  int CPhidgetSpatial_setDataRate(CPhidgetSpatialHandle phid, int milliseconds);
00661  int CPhidgetSpatial_getDataRateMax(CPhidgetSpatialHandle phid, int *max);
00662  int CPhidgetSpatial_getDataRateMin(CPhidgetSpatialHandle phid, int *min);
00663  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);
00664  int CPhidgetSpatial_resetCompassCorrectionParameters(CPhidgetSpatialHandle phid);
00665  int CPhidgetSpatial_set_OnSpatialData_Handler(CPhidgetSpatialHandle phid, int ( *fptr)(CPhidgetSpatialHandle phid, void *userPtr, CPhidgetSpatial_SpatialEventDataHandle *data, int dataCount), void *userPtr);
00666 typedef struct _CPhidgetStepper *CPhidgetStepperHandle;
00667  int CPhidgetStepper_create(CPhidgetStepperHandle *phid);
00668  int CPhidgetStepper_getInputCount(CPhidgetStepperHandle phid, int *count);
00669  int CPhidgetStepper_getInputState(CPhidgetStepperHandle phid, int index, int *inputState);
00670  int CPhidgetStepper_set_OnInputChange_Handler(CPhidgetStepperHandle phid, int ( *fptr)(CPhidgetStepperHandle phid, void *userPtr, int index, int inputState), void *userPtr);
00671  int CPhidgetStepper_getMotorCount(CPhidgetStepperHandle phid, int *count);
00672  int CPhidgetStepper_getAcceleration(CPhidgetStepperHandle phid, int index, double *acceleration);
00673  int CPhidgetStepper_setAcceleration(CPhidgetStepperHandle phid, int index, double acceleration);
00674  int CPhidgetStepper_getAccelerationMax(CPhidgetStepperHandle phid, int index, double *max);
00675  int CPhidgetStepper_getAccelerationMin(CPhidgetStepperHandle phid, int index, double *min);
00676  int CPhidgetStepper_getVelocityLimit(CPhidgetStepperHandle phid, int index, double *limit);
00677  int CPhidgetStepper_setVelocityLimit(CPhidgetStepperHandle phid, int index, double limit);
00678  int CPhidgetStepper_getVelocity(CPhidgetStepperHandle phid, int index, double *velocity);
00679  int CPhidgetStepper_getVelocityMax(CPhidgetStepperHandle phid, int index, double *max);
00680  int CPhidgetStepper_getVelocityMin(CPhidgetStepperHandle phid, int index, double *min);
00681  int CPhidgetStepper_set_OnVelocityChange_Handler(CPhidgetStepperHandle phid, int ( *fptr)(CPhidgetStepperHandle phid, void *userPtr, int index, double velocity), void *userPtr);
00682  int CPhidgetStepper_getTargetPosition(CPhidgetStepperHandle phid, int index, __int64 *position);
00683  int CPhidgetStepper_setTargetPosition(CPhidgetStepperHandle phid, int index, __int64 position);
00684  int CPhidgetStepper_getCurrentPosition(CPhidgetStepperHandle phid, int index, __int64 *position);
00685  int CPhidgetStepper_setCurrentPosition(CPhidgetStepperHandle phid, int index, __int64 position);
00686  int CPhidgetStepper_getPositionMax(CPhidgetStepperHandle phid, int index, __int64 *max);
00687  int CPhidgetStepper_getPositionMin(CPhidgetStepperHandle phid, int index, __int64 *min);
00688  int CPhidgetStepper_set_OnPositionChange_Handler(CPhidgetStepperHandle phid, int ( *fptr)(CPhidgetStepperHandle phid, void *userPtr, int index, __int64 position), void *userPtr);
00689  int CPhidgetStepper_getCurrentLimit(CPhidgetStepperHandle phid, int index, double *limit);
00690  int CPhidgetStepper_setCurrentLimit(CPhidgetStepperHandle phid, int index, double limit);
00691  int CPhidgetStepper_getCurrent(CPhidgetStepperHandle phid, int index, double *current);
00692  int CPhidgetStepper_getCurrentMax(CPhidgetStepperHandle phid, int index, double *max);
00693  int CPhidgetStepper_getCurrentMin(CPhidgetStepperHandle phid, int index, double *min);
00694  int CPhidgetStepper_set_OnCurrentChange_Handler(CPhidgetStepperHandle phid, int ( *fptr)(CPhidgetStepperHandle phid, void *userPtr, int index, double current), void *userPtr);
00695  int CPhidgetStepper_getEngaged(CPhidgetStepperHandle phid, int index, int *engagedState);
00696  int CPhidgetStepper_setEngaged(CPhidgetStepperHandle phid, int index, int engagedState);
00697  int CPhidgetStepper_getStopped(CPhidgetStepperHandle phid, int index, int *stoppedState);
00698 typedef struct _CPhidgetTemperatureSensor *CPhidgetTemperatureSensorHandle;
00699  int CPhidgetTemperatureSensor_create(CPhidgetTemperatureSensorHandle *phid);
00700 typedef enum {
00701  PHIDGET_TEMPERATURE_SENSOR_K_TYPE = 1,
00702  PHIDGET_TEMPERATURE_SENSOR_J_TYPE,
00703  PHIDGET_TEMPERATURE_SENSOR_E_TYPE,
00704  PHIDGET_TEMPERATURE_SENSOR_T_TYPE
00705 } CPhidgetTemperatureSensor_ThermocoupleType;
00706  int CPhidgetTemperatureSensor_getTemperatureInputCount(CPhidgetTemperatureSensorHandle phid, int *count);
00707  int CPhidgetTemperatureSensor_getTemperature(CPhidgetTemperatureSensorHandle phid, int index, double *temperature);
00708  int CPhidgetTemperatureSensor_getTemperatureMax(CPhidgetTemperatureSensorHandle phid, int index, double *max);
00709  int CPhidgetTemperatureSensor_getTemperatureMin(CPhidgetTemperatureSensorHandle phid, int index, double *min);
00710  int CPhidgetTemperatureSensor_set_OnTemperatureChange_Handler(CPhidgetTemperatureSensorHandle phid, int ( *fptr)(CPhidgetTemperatureSensorHandle phid, void *userPtr, int index, double temperature), void *userPtr);
00711  int CPhidgetTemperatureSensor_getTemperatureChangeTrigger(CPhidgetTemperatureSensorHandle phid, int index, double *trigger);
00712  int CPhidgetTemperatureSensor_setTemperatureChangeTrigger(CPhidgetTemperatureSensorHandle phid, int index, double trigger);
00713  int CPhidgetTemperatureSensor_getPotential(CPhidgetTemperatureSensorHandle phid, int index, double *potential);
00714  int CPhidgetTemperatureSensor_getPotentialMax(CPhidgetTemperatureSensorHandle phid, int index, double *max);
00715  int CPhidgetTemperatureSensor_getPotentialMin(CPhidgetTemperatureSensorHandle phid, int index, double *min);
00716  int CPhidgetTemperatureSensor_getAmbientTemperature(CPhidgetTemperatureSensorHandle phid, double *ambient);
00717  int CPhidgetTemperatureSensor_getAmbientTemperatureMax(CPhidgetTemperatureSensorHandle phid, double *max);
00718  int CPhidgetTemperatureSensor_getAmbientTemperatureMin(CPhidgetTemperatureSensorHandle phid, double *min);
00719  int CPhidgetTemperatureSensor_getThermocoupleType(CPhidgetTemperatureSensorHandle phid, int index, CPhidgetTemperatureSensor_ThermocoupleType *type);
00720  int CPhidgetTemperatureSensor_setThermocoupleType(CPhidgetTemperatureSensorHandle phid, int index, CPhidgetTemperatureSensor_ThermocoupleType type);
00721 typedef struct _CPhidgetTextLCD *CPhidgetTextLCDHandle;
00722  int CPhidgetTextLCD_create(CPhidgetTextLCDHandle *phid);
00723  int CPhidgetTextLCD_getRowCount(CPhidgetTextLCDHandle phid, int *count);
00724  int CPhidgetTextLCD_getColumnCount(CPhidgetTextLCDHandle phid, int *count);
00725  int CPhidgetTextLCD_getBacklight(CPhidgetTextLCDHandle phid, int *backlightState);
00726  int CPhidgetTextLCD_setBacklight(CPhidgetTextLCDHandle phid, int backlightState);
00727  int CPhidgetTextLCD_getBrightness(CPhidgetTextLCDHandle phid, int *brightness);
00728  int CPhidgetTextLCD_setBrightness(CPhidgetTextLCDHandle phid, int brightness);
00729  int CPhidgetTextLCD_getContrast(CPhidgetTextLCDHandle phid, int *contrast);
00730  int CPhidgetTextLCD_setContrast(CPhidgetTextLCDHandle phid, int contrast);
00731  int CPhidgetTextLCD_getCursorOn(CPhidgetTextLCDHandle phid, int *cursorState);
00732  int CPhidgetTextLCD_setCursorOn(CPhidgetTextLCDHandle phid, int cursorState);
00733  int CPhidgetTextLCD_getCursorBlink(CPhidgetTextLCDHandle phid, int *cursorBlinkState);
00734  int CPhidgetTextLCD_setCursorBlink(CPhidgetTextLCDHandle phid, int cursorBlinkState);
00735  int CPhidgetTextLCD_setCustomCharacter(CPhidgetTextLCDHandle phid, int index, int var1,int var2);
00736  int CPhidgetTextLCD_setDisplayCharacter(CPhidgetTextLCDHandle phid, int index, int column,unsigned char character);
00737  int CPhidgetTextLCD_setDisplayString(CPhidgetTextLCDHandle phid, int index, char *displayString);
00738 typedef enum {
00739  PHIDGET_TEXTLCD_SCREEN_NONE = 1,
00740  PHIDGET_TEXTLCD_SCREEN_1x8,
00741  PHIDGET_TEXTLCD_SCREEN_2x8,
00742  PHIDGET_TEXTLCD_SCREEN_1x16,
00743  PHIDGET_TEXTLCD_SCREEN_2x16,
00744  PHIDGET_TEXTLCD_SCREEN_4x16,
00745  PHIDGET_TEXTLCD_SCREEN_2x20,
00746  PHIDGET_TEXTLCD_SCREEN_4x20,
00747  PHIDGET_TEXTLCD_SCREEN_2x24,
00748  PHIDGET_TEXTLCD_SCREEN_1x40,
00749  PHIDGET_TEXTLCD_SCREEN_2x40,
00750  PHIDGET_TEXTLCD_SCREEN_4x40,
00751  PHIDGET_TEXTLCD_SCREEN_UNKNOWN
00752 } CPhidgetTextLCD_ScreenSize;
00753  int CPhidgetTextLCD_getScreenCount(CPhidgetTextLCDHandle phid, int *count);
00754  int CPhidgetTextLCD_getScreen(CPhidgetTextLCDHandle phid, int *screenIndex);
00755  int CPhidgetTextLCD_setScreen(CPhidgetTextLCDHandle phid, int screenIndex);
00756  int CPhidgetTextLCD_getScreenSize(CPhidgetTextLCDHandle phid, CPhidgetTextLCD_ScreenSize *screenSize);
00757  int CPhidgetTextLCD_setScreenSize(CPhidgetTextLCDHandle phid, CPhidgetTextLCD_ScreenSize screenSize);
00758  int CPhidgetTextLCD_initialize(CPhidgetTextLCDHandle phid);
00759 typedef struct _CPhidgetTextLED *CPhidgetTextLEDHandle;
00760  int CPhidgetTextLED_create(CPhidgetTextLEDHandle *phid);
00761  int CPhidgetTextLED_getRowCount(CPhidgetTextLEDHandle phid, int *count);
00762  int CPhidgetTextLED_getColumnCount(CPhidgetTextLEDHandle phid, int *count);
00763  int CPhidgetTextLED_getBrightness(CPhidgetTextLEDHandle phid, int *brightness);
00764  int CPhidgetTextLED_setBrightness(CPhidgetTextLEDHandle phid, int brightness);
00765  int CPhidgetTextLED_setDisplayString(CPhidgetTextLEDHandle phid, int index, char *displayString);
00766 typedef struct _CPhidgetWeightSensor *CPhidgetWeightSensorHandle;
00767  int CPhidgetWeightSensor_create(CPhidgetWeightSensorHandle *phid);
00768  int CPhidgetWeightSensor_getWeight(CPhidgetWeightSensorHandle phid, double *weight);
00769  int CPhidgetWeightSensor_set_OnWeightChange_Handler(CPhidgetWeightSensorHandle phid, int ( *fptr)(CPhidgetWeightSensorHandle phid, void *userPtr, double weight), void *userPtr);
00770  int CPhidgetWeightSensor_getWeightChangeTrigger(CPhidgetWeightSensorHandle phid, double *trigger);
00771  int CPhidgetWeightSensor_setWeightChangeTrigger(CPhidgetWeightSensorHandle phid, double trigger);
00772 #ifndef CPHIDGET_CONSTANTS
00773 #define CPHIDGET_CONSTANTS
00774 
00784 #define PHIDGET_ATTACHED                                0x1 
00785 #define PHIDGET_NOTATTACHED                             0x0 
00788 //Adding error codes: Update .NET, COM, Python, Java
00789 
00793 #define PHIDGET_ERROR_CODE_COUNT                20
00794 #define EPHIDGET_OK                                             0       
00795 #define EPHIDGET_NOTFOUND                               1       
00796 #define EPHIDGET_NOMEMORY                               2       
00797 #define EPHIDGET_UNEXPECTED                             3       
00798 #define EPHIDGET_INVALIDARG                             4       
00799 #define EPHIDGET_NOTATTACHED                    5       
00800 #define EPHIDGET_INTERRUPTED                    6       
00801 #define EPHIDGET_INVALID                                7       
00802 #define EPHIDGET_NETWORK                                8       
00803 #define EPHIDGET_UNKNOWNVAL                             9       
00804 #define EPHIDGET_BADPASSWORD                    10      
00805 #define EPHIDGET_UNSUPPORTED                    11      
00806 #define EPHIDGET_DUPLICATE                              12      
00807 #define EPHIDGET_TIMEOUT                                13      
00808 #define EPHIDGET_OUTOFBOUNDS                    14      
00809 #define EPHIDGET_EVENT                                  15      
00810 #define EPHIDGET_NETWORK_NOTCONNECTED   16      
00811 #define EPHIDGET_WRONGDEVICE                    17      
00812 #define EPHIDGET_CLOSED                                 18      
00813 #define EPHIDGET_BADVERSION                             19      
00816 //Adding error codes: Update .NET, COM, Python, Java
00817 
00821 #define EEPHIDGET_EVENT_ERROR(code) (0x8000 + code)
00822 
00823 
00824 //Library errors
00825 #define EEPHIDGET_NETWORK               EEPHIDGET_EVENT_ERROR(0x0001)   
00826 #define EEPHIDGET_BADPASSWORD   EEPHIDGET_EVENT_ERROR(0x0002)   
00827 #define EEPHIDGET_BADVERSION    EEPHIDGET_EVENT_ERROR(0x0003)   
00829 //Errors streamed back from firmware
00830 #define EEPHIDGET_OK                    EEPHIDGET_EVENT_ERROR(0x1000)   
00831 #define EEPHIDGET_OVERRUN               EEPHIDGET_EVENT_ERROR(0x1002)   
00832 #define EEPHIDGET_PACKETLOST    EEPHIDGET_EVENT_ERROR(0x1003)   
00833 #define EEPHIDGET_WRAP                  EEPHIDGET_EVENT_ERROR(0x1004)   
00834 #define EEPHIDGET_OVERTEMP              EEPHIDGET_EVENT_ERROR(0x1005)   
00835 #define EEPHIDGET_OVERCURRENT   EEPHIDGET_EVENT_ERROR(0x1006)   
00836 #define EEPHIDGET_OUTOFRANGE    EEPHIDGET_EVENT_ERROR(0x1007)   
00837 #define EEPHIDGET_BADPOWER              EEPHIDGET_EVENT_ERROR(0x1008)   
00845 #define PUNK_BOOL       0x02                                    
00846 #define PUNK_SHRT       0x7FFF                                  
00847 #define PUNK_INT        0x7FFFFFFF                              
00848 #define PUNK_INT64      0x7FFFFFFFFFFFFFFFLL    
00849 #define PUNK_DBL        1e300                                   
00850 #define PUNK_FLT        1e30                                    
00853 #define PFALSE          0x00    
00854 #define PTRUE           0x01    
00858 #endif
00859 
00860 #ifdef __cplusplus
00861 }
00862 #endif


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