00001 #ifndef PHIDGET_H
00002 #define PHIDGET_H
00003 #ifdef __cplusplus
00004 extern "C" {
00005 #endif
00006 typedef struct _CPhidget *CPhidgetHandle;
00007 typedef long long __int64;
00008 typedef struct _CPhidget_Timestamp {
00009 int seconds;
00010 int microseconds;
00011 } CPhidget_Timestamp, *CPhidget_TimestampHandle;
00012 typedef enum {
00013 PHIDCLASS_ACCELEROMETER = 2,
00014 PHIDCLASS_ADVANCEDSERVO = 3,
00015 PHIDCLASS_ENCODER = 4,
00016 PHIDCLASS_INTERFACEKIT = 7,
00017 PHIDCLASS_IR = 19,
00018 PHIDCLASS_LED = 8,
00019 PHIDCLASS_MOTORCONTROL = 9,
00020 PHIDCLASS_PHSENSOR = 10,
00021 PHIDCLASS_RFID = 11,
00022 PHIDCLASS_SERVO = 12,
00023 PHIDCLASS_STEPPER = 13,
00024 PHIDCLASS_TEMPERATURESENSOR = 14,
00025 PHIDCLASS_TEXTLCD = 15,
00026 PHIDCLASS_TEXTLED = 16,
00027 PHIDCLASS_WEIGHTSENSOR = 17,
00028 PHIDCLASS_SPATIAL = 20,
00029 } CPhidget_DeviceClass;
00030 typedef enum {
00031 PHIDID_ACCELEROMETER_3AXIS = 0x07E,
00032 PHIDID_ADVANCEDSERVO_1MOTOR = 0x082,
00033 PHIDID_ADVANCEDSERVO_8MOTOR = 0x03A,
00034 PHIDID_BIPOLAR_STEPPER_1MOTOR = 0x07B,
00035 PHIDID_ENCODER_1ENCODER_1INPUT = 0x04B,
00036 PHIDID_ENCODER_HS_1ENCODER = 0x080,
00037 PHIDID_ENCODER_HS_4ENCODER_4INPUT = 0x04F,
00038 PHIDID_INTERFACEKIT_0_0_4 = 0x040,
00039 PHIDID_INTERFACEKIT_0_0_8 = 0x081,
00040 PHIDID_INTERFACEKIT_0_16_16 = 0x044,
00041 PHIDID_INTERFACEKIT_8_8_8 = 0x045,
00042 PHIDID_INTERFACEKIT_8_8_8_w_LCD = 0x07D,
00043 PHIDID_IR = 0x04D,
00044 PHIDID_LED_64 = 0x04A,
00045 PHIDID_LED_64_ADV = 0x04C,
00046 PHIDID_LINEAR_TOUCH = 0x076,
00047 PHIDID_MOTORCONTROL_HC_2MOTOR = 0x059,
00048 PHIDID_MOTORCONTROL_LV_2MOTOR_4INPUT = 0x058,
00049 PHIDID_PHSENSOR = 0x074,
00050 PHIDID_RFID_2OUTPUT = 0x031,
00051 PHIDID_ROTARY_TOUCH = 0x077,
00052 PHIDID_SERVO_1MOTOR = 0x039,
00053 PHIDID_SPATIAL_ACCEL_3AXIS = 0x07F,
00054 PHIDID_SPATIAL_ACCEL_GYRO_COMPASS = 0x033,
00055 PHIDID_TEMPERATURESENSOR = 0x070,
00056 PHIDID_TEMPERATURESENSOR_4 = 0x032,
00057 PHIDID_TEXTLCD_2x20_w_8_8_8 = 0x17D,
00058 PHIDID_UNIPOLAR_STEPPER_4MOTOR = 0x07A,
00059 PHIDID_ACCELEROMETER_2AXIS = 0x071,
00060 PHIDID_INTERFACEKIT_0_8_8_w_LCD = 0x053,
00061 PHIDID_INTERFACEKIT_4_8_8 = 4,
00062 PHIDID_RFID = 0x030,
00063 PHIDID_SERVO_1MOTOR_OLD = 2,
00064 PHIDID_SERVO_4MOTOR = 0x038,
00065 PHIDID_SERVO_4MOTOR_OLD = 3,
00066 PHIDID_TEXTLCD_2x20 = 0x052,
00067 PHIDID_TEXTLCD_2x20_w_0_8_8 = 0x153,
00068 PHIDID_TEXTLED_1x8 = 0x049,
00069 PHIDID_TEXTLED_4x8 = 0x048,
00070 PHIDID_WEIGHTSENSOR = 0x072,
00071 } CPhidget_DeviceID;
00072 int CPhidget_open(CPhidgetHandle phid, int serialNumber);
00073 int CPhidget_close(CPhidgetHandle phid);
00074 int CPhidget_delete(CPhidgetHandle phid);
00075 int CPhidget_set_OnDetach_Handler(CPhidgetHandle phid, int( *fptr)(CPhidgetHandle phid, void *userPtr), void *userPtr);
00076 int CPhidget_set_OnAttach_Handler(CPhidgetHandle phid, int( *fptr)(CPhidgetHandle phid, void *userPtr), void *userPtr);
00077 int CPhidget_set_OnServerConnect_Handler(CPhidgetHandle phid, int ( *fptr)(CPhidgetHandle phid, void *userPtr), void *userPtr);
00078 int CPhidget_set_OnServerDisconnect_Handler(CPhidgetHandle phid, int ( *fptr)(CPhidgetHandle phid, void *userPtr), void *userPtr);
00079 int CPhidget_set_OnError_Handler(CPhidgetHandle phid, int( *fptr)(CPhidgetHandle phid, void *userPtr, int errorCode, const char *errorString), void *userPtr);
00080 int CPhidget_getDeviceName(CPhidgetHandle phid, const char **deviceName);
00081 int CPhidget_getSerialNumber(CPhidgetHandle phid, int *serialNumber);
00082 int CPhidget_getDeviceVersion(CPhidgetHandle phid, int *deviceVersion);
00083 int CPhidget_getDeviceStatus(CPhidgetHandle phid, int *deviceStatus);
00084 int CPhidget_getLibraryVersion(const char **libraryVersion);
00085 int CPhidget_getDeviceType(CPhidgetHandle phid, const char **deviceType);
00086 int CPhidget_getDeviceLabel(CPhidgetHandle phid, const char **deviceLabel);
00087 int CPhidget_setDeviceLabel(CPhidgetHandle phid, const char *deviceLabel);
00088 int CPhidget_getErrorDescription(int errorCode, const char **errorString);
00089 int CPhidget_waitForAttachment(CPhidgetHandle phid, int milliseconds);
00090 int CPhidget_getServerID(CPhidgetHandle phid, const char **serverID);
00091 int CPhidget_getServerAddress(CPhidgetHandle phid, const char **address, int *port);
00092 int CPhidget_getServerStatus(CPhidgetHandle phid, int *serverStatus);
00093 int CPhidget_getDeviceID(CPhidgetHandle phid, CPhidget_DeviceID *deviceID);
00094 int CPhidget_getDeviceClass(CPhidgetHandle phid, CPhidget_DeviceClass *deviceClass);
00095 typedef enum {
00096 PHIDGET_DICTIONARY_VALUE_CHANGED = 1,
00097 PHIDGET_DICTIONARY_ENTRY_ADDED,
00098 PHIDGET_DICTIONARY_ENTRY_REMOVING,
00099 PHIDGET_DICTIONARY_CURRENT_VALUE
00100 } CPhidgetDictionary_keyChangeReason;
00101 typedef struct _CPhidgetDictionary *CPhidgetDictionaryHandle;
00102 typedef struct _CPhidgetDictionaryListener *CPhidgetDictionaryListenerHandle;
00103 int CPhidgetDictionary_create(CPhidgetDictionaryHandle *dict);
00104 int CPhidgetDictionary_close(CPhidgetDictionaryHandle dict);
00105 int CPhidgetDictionary_delete(CPhidgetDictionaryHandle dict);
00106 int CPhidgetDictionary_set_OnError_Handler(CPhidgetDictionaryHandle dict,
00107 int( *fptr)(CPhidgetDictionaryHandle, void *userPtr, int errorCode, const char *errorString), void *userPtr);
00108 int CPhidgetDictionary_addKey(CPhidgetDictionaryHandle dict, const char *key, const char *value, int persistent);
00109
00110
00111
00112
00113
00114 int CPhidgetDictionary_removeKey(CPhidgetDictionaryHandle dict, const char *pattern);
00115 typedef int( *CPhidgetDictionary_OnKeyChange_Function)(CPhidgetDictionaryHandle dict, void *userPtr,
00116 const char *key, const char *value, CPhidgetDictionary_keyChangeReason reason);
00117 int CPhidgetDictionary_set_OnKeyChange_Handler(CPhidgetDictionaryHandle dict, CPhidgetDictionaryListenerHandle *dictlistener, const char *pattern,
00118 CPhidgetDictionary_OnKeyChange_Function fptr, void *userPtr);
00119 int CPhidgetDictionary_remove_OnKeyChange_Handler(CPhidgetDictionaryListenerHandle dictlistener);
00120 int CPhidgetDictionary_getKey(CPhidgetDictionaryHandle dict, const char *key, char *value, int valuelen);
00121 int CPhidgetDictionary_set_OnServerConnect_Handler(CPhidgetDictionaryHandle dict, int ( *fptr)(CPhidgetDictionaryHandle dict, void *userPtr), void *userPtr);
00122 int CPhidgetDictionary_set_OnServerDisconnect_Handler(CPhidgetDictionaryHandle dict, int ( *fptr)(CPhidgetDictionaryHandle dict, void *userPtr), void *userPtr);
00123 int CPhidgetDictionary_getServerID(CPhidgetDictionaryHandle dict, const char **serverID);
00124 int CPhidgetDictionary_getServerAddress(CPhidgetDictionaryHandle dict, const char **address, int *port);
00125 int CPhidgetDictionary_getServerStatus(CPhidgetDictionaryHandle dict, int *serverStatus);
00126 typedef struct _CPhidgetManager *CPhidgetManagerHandle;
00127 int CPhidgetManager_create(CPhidgetManagerHandle *phidm);
00128 int CPhidgetManager_open(CPhidgetManagerHandle phidm);
00129 int CPhidgetManager_close(CPhidgetManagerHandle phidm);
00130 int CPhidgetManager_delete(CPhidgetManagerHandle phidm);
00131 int CPhidgetManager_set_OnAttach_Handler(CPhidgetManagerHandle phidm, int ( *fptr)(CPhidgetHandle phid, void *userPtr), void *userPtr);
00132 int CPhidgetManager_set_OnDetach_Handler(CPhidgetManagerHandle phidm, int ( *fptr)(CPhidgetHandle phid, void *userPtr), void *userPtr);
00133 int CPhidgetManager_getAttachedDevices(CPhidgetManagerHandle phidm, CPhidgetHandle *phidArray[], int *count);
00134 int CPhidgetManager_freeAttachedDevicesArray(CPhidgetHandle phidArray[]);
00135 int CPhidgetManager_set_OnError_Handler(CPhidgetManagerHandle phidm, int( *fptr)(CPhidgetManagerHandle phidm, void *userPtr, int errorCode, const char *errorString), void *userPtr);
00136 int CPhidgetManager_set_OnServerConnect_Handler(CPhidgetManagerHandle phidm, int ( *fptr)(CPhidgetManagerHandle phidm, void *userPtr), void *userPtr);
00137 int CPhidgetManager_set_OnServerDisconnect_Handler(CPhidgetManagerHandle phidm, int ( *fptr)(CPhidgetManagerHandle phidm, void *userPtr), void *userPtr);
00138
00139
00140 int CPhidgetManager_getServerID(CPhidgetManagerHandle phidm, const char **serverID);
00141
00142
00143
00144
00145
00146
00147 int CPhidgetManager_getServerAddress(CPhidgetManagerHandle phidm, const char **address, int *port);
00148
00149
00150
00151
00152
00153 int CPhidgetManager_getServerStatus(CPhidgetManagerHandle phidm, int *serverStatus);
00154 int CPhidget_openRemote(CPhidgetHandle phid, int serial, const char *serverID, const char *password);
00155 int CPhidget_openRemoteIP(CPhidgetHandle phid, int serial, const char *address, int port, const char *password);
00156 int CPhidgetManager_openRemote(CPhidgetManagerHandle phidm, const char *serverID, const char *password);
00157 int CPhidgetManager_openRemoteIP(CPhidgetManagerHandle phidm, const char *address, int port, const char *password);
00158 int CPhidgetDictionary_openRemote(CPhidgetDictionaryHandle dict, const char *serverID, const char *password);
00159 int CPhidgetDictionary_openRemoteIP(CPhidgetDictionaryHandle dict, const char *address, int port, const char *password);
00160 typedef enum {
00161 PHIDGET_LOG_CRITICAL = 1,
00162 PHIDGET_LOG_ERROR,
00163 PHIDGET_LOG_WARNING,
00164 PHIDGET_LOG_DEBUG,
00165 PHIDGET_LOG_INFO,
00166 PHIDGET_LOG_VERBOSE
00167 } CPhidgetLog_level;
00168 int CPhidget_enableLogging(CPhidgetLog_level level, const char *outputFile);
00169 int CPhidget_disableLogging();
00170 int CPhidget_log(CPhidgetLog_level level, const char *id, const char *message, ...);
00171 typedef struct _CPhidgetAccelerometer *CPhidgetAccelerometerHandle;
00172 int CPhidgetAccelerometer_create(CPhidgetAccelerometerHandle *phid);
00173 int CPhidgetAccelerometer_getAxisCount(CPhidgetAccelerometerHandle phid, int *count);
00174 int CPhidgetAccelerometer_getAcceleration(CPhidgetAccelerometerHandle phid, int index, double *acceleration);
00175 int CPhidgetAccelerometer_getAccelerationMax(CPhidgetAccelerometerHandle phid, int index, double *max);
00176 int CPhidgetAccelerometer_getAccelerationMin(CPhidgetAccelerometerHandle phid, int index, double *min);
00177 int CPhidgetAccelerometer_set_OnAccelerationChange_Handler(CPhidgetAccelerometerHandle phid, int ( *fptr)(CPhidgetAccelerometerHandle phid, void *userPtr, int index, double acceleration), void *userPtr);
00178 int CPhidgetAccelerometer_getAccelerationChangeTrigger(CPhidgetAccelerometerHandle phid, int index, double *trigger);
00179 int CPhidgetAccelerometer_setAccelerationChangeTrigger(CPhidgetAccelerometerHandle phid, int index, double trigger);
00180 typedef struct _CPhidgetAdvancedServo *CPhidgetAdvancedServoHandle;
00181 int CPhidgetAdvancedServo_create(CPhidgetAdvancedServoHandle *phid);
00182 typedef enum {
00183 PHIDGET_SERVO_DEFAULT = 1,
00184 PHIDGET_SERVO_RAW_us_MODE,
00185 PHIDGET_SERVO_HITEC_HS322HD,
00186 PHIDGET_SERVO_HITEC_HS5245MG,
00187 PHIDGET_SERVO_HITEC_805BB,
00188 PHIDGET_SERVO_HITEC_HS422,
00189 PHIDGET_SERVO_TOWERPRO_MG90,
00190 PHIDGET_SERVO_HITEC_HSR1425CR,
00191 PHIDGET_SERVO_HITEC_HS785HB,
00192 PHIDGET_SERVO_HITEC_HS485HB,
00193 PHIDGET_SERVO_HITEC_HS645MG,
00194 PHIDGET_SERVO_HITEC_815BB,
00195 PHIDGET_SERVO_FIRGELLI_L12_30_50_06_R,
00196 PHIDGET_SERVO_FIRGELLI_L12_50_100_06_R,
00197 PHIDGET_SERVO_FIRGELLI_L12_50_210_06_R,
00198 PHIDGET_SERVO_FIRGELLI_L12_100_50_06_R,
00199 PHIDGET_SERVO_FIRGELLI_L12_100_100_06_R,
00200 PHIDGET_SERVO_USER_DEFINED
00201 } CPhidget_ServoType;
00202 int CPhidgetAdvancedServo_getMotorCount(CPhidgetAdvancedServoHandle phid, int *count);
00203 int CPhidgetAdvancedServo_getAcceleration(CPhidgetAdvancedServoHandle phid, int index, double *acceleration);
00204 int CPhidgetAdvancedServo_setAcceleration(CPhidgetAdvancedServoHandle phid, int index, double acceleration);
00205 int CPhidgetAdvancedServo_getAccelerationMax(CPhidgetAdvancedServoHandle phid, int index, double *max);
00206 int CPhidgetAdvancedServo_getAccelerationMin(CPhidgetAdvancedServoHandle phid, int index, double *min);
00207 int CPhidgetAdvancedServo_getVelocityLimit(CPhidgetAdvancedServoHandle phid, int index, double *limit);
00208 int CPhidgetAdvancedServo_setVelocityLimit(CPhidgetAdvancedServoHandle phid, int index, double limit);
00209 int CPhidgetAdvancedServo_getVelocity(CPhidgetAdvancedServoHandle phid, int index, double *velocity);
00210 int CPhidgetAdvancedServo_getVelocityMax(CPhidgetAdvancedServoHandle phid, int index, double *max);
00211 int CPhidgetAdvancedServo_getVelocityMin(CPhidgetAdvancedServoHandle phid, int index, double *min);
00212 int CPhidgetAdvancedServo_set_OnVelocityChange_Handler(CPhidgetAdvancedServoHandle phid, int ( *fptr)(CPhidgetAdvancedServoHandle phid, void *userPtr, int index, double velocity), void *userPtr);
00213 int CPhidgetAdvancedServo_getPosition(CPhidgetAdvancedServoHandle phid, int index, double *position);
00214 int CPhidgetAdvancedServo_setPosition(CPhidgetAdvancedServoHandle phid, int index, double position);
00215 int CPhidgetAdvancedServo_getPositionMax(CPhidgetAdvancedServoHandle phid, int index, double *max);
00216 int CPhidgetAdvancedServo_setPositionMax(CPhidgetAdvancedServoHandle phid, int index, double max);
00217 int CPhidgetAdvancedServo_getPositionMin(CPhidgetAdvancedServoHandle phid, int index, double *min);
00218 int CPhidgetAdvancedServo_setPositionMin(CPhidgetAdvancedServoHandle phid, int index, double min);
00219 int CPhidgetAdvancedServo_set_OnPositionChange_Handler(CPhidgetAdvancedServoHandle phid, int ( *fptr)(CPhidgetAdvancedServoHandle phid, void *userPtr, int index, double position), void *userPtr);
00220 int CPhidgetAdvancedServo_getCurrent(CPhidgetAdvancedServoHandle phid, int index, double *current);
00221 int CPhidgetAdvancedServo_set_OnCurrentChange_Handler(CPhidgetAdvancedServoHandle phid, int ( *fptr)(CPhidgetAdvancedServoHandle phid, void *userPtr, int index, double current), void *userPtr);
00222 int CPhidgetAdvancedServo_getSpeedRampingOn(CPhidgetAdvancedServoHandle phid, int index, int *rampingState);
00223 int CPhidgetAdvancedServo_setSpeedRampingOn(CPhidgetAdvancedServoHandle phid, int index, int rampingState);
00224 int CPhidgetAdvancedServo_getEngaged(CPhidgetAdvancedServoHandle phid, int index, int *engagedState);
00225 int CPhidgetAdvancedServo_setEngaged(CPhidgetAdvancedServoHandle phid, int index, int engagedState);
00226 int CPhidgetAdvancedServo_getStopped(CPhidgetAdvancedServoHandle phid, int index, int *stoppedState);
00227
00228
00229
00230
00231 int CPhidgetAdvancedServo_getServoType(CPhidgetAdvancedServoHandle phid, int index, CPhidget_ServoType *servoType);
00232
00233
00234
00235
00236
00237
00238 int CPhidgetAdvancedServo_setServoType(CPhidgetAdvancedServoHandle phid, int index, CPhidget_ServoType servoType);
00239 int CPhidgetAdvancedServo_setServoParameters(CPhidgetAdvancedServoHandle phid, int index, double min_us,double max_us,double degrees,double velocity_max);
00240 typedef struct _CPhidgetEncoder *CPhidgetEncoderHandle;
00241 int CPhidgetEncoder_create(CPhidgetEncoderHandle *phid);
00242 int CPhidgetEncoder_getInputCount(CPhidgetEncoderHandle phid, int *count);
00243 int CPhidgetEncoder_getInputState(CPhidgetEncoderHandle phid, int index, int *inputState);
00244 int CPhidgetEncoder_set_OnInputChange_Handler(CPhidgetEncoderHandle phid, int ( *fptr)(CPhidgetEncoderHandle phid, void *userPtr, int index, int inputState), void *userPtr);
00245 int CPhidgetEncoder_getEncoderCount(CPhidgetEncoderHandle phid, int *count);
00246 int CPhidgetEncoder_getPosition(CPhidgetEncoderHandle phid, int index, int *position);
00247 int CPhidgetEncoder_setPosition(CPhidgetEncoderHandle phid, int index, int position);
00248 int CPhidgetEncoder_set_OnPositionChange_Handler(CPhidgetEncoderHandle phid, int ( *fptr)(CPhidgetEncoderHandle phid, void *userPtr, int index, int time,int positionChange), void *userPtr);
00249 int CPhidgetEncoder_getIndexPosition(CPhidgetEncoderHandle phid, int index, int *position);
00250 int CPhidgetEncoder_getEnabled(CPhidgetEncoderHandle phid, int index, int *enabledState);
00251 int CPhidgetEncoder_setEnabled(CPhidgetEncoderHandle phid, int index, int enabledState);
00252 typedef struct _CPhidgetInterfaceKit *CPhidgetInterfaceKitHandle;
00253 int CPhidgetInterfaceKit_create(CPhidgetInterfaceKitHandle *phid);
00254 int CPhidgetInterfaceKit_getInputCount(CPhidgetInterfaceKitHandle phid, int *count);
00255 int CPhidgetInterfaceKit_getInputState(CPhidgetInterfaceKitHandle phid, int index, int *inputState);
00256 int CPhidgetInterfaceKit_set_OnInputChange_Handler(CPhidgetInterfaceKitHandle phid, int ( *fptr)(CPhidgetInterfaceKitHandle phid, void *userPtr, int index, int inputState), void *userPtr);
00257 int CPhidgetInterfaceKit_getOutputCount(CPhidgetInterfaceKitHandle phid, int *count);
00258 int CPhidgetInterfaceKit_getOutputState(CPhidgetInterfaceKitHandle phid, int index, int *outputState);
00259 int CPhidgetInterfaceKit_setOutputState(CPhidgetInterfaceKitHandle phid, int index, int outputState);
00260 int CPhidgetInterfaceKit_set_OnOutputChange_Handler(CPhidgetInterfaceKitHandle phid, int ( *fptr)(CPhidgetInterfaceKitHandle phid, void *userPtr, int index, int outputState), void *userPtr);
00261 int CPhidgetInterfaceKit_getSensorCount(CPhidgetInterfaceKitHandle phid, int *count);
00262 int CPhidgetInterfaceKit_getSensorValue(CPhidgetInterfaceKitHandle phid, int index, int *sensorValue);
00263 int CPhidgetInterfaceKit_getSensorRawValue(CPhidgetInterfaceKitHandle phid, int index, int *sensorRawValue);
00264 int CPhidgetInterfaceKit_set_OnSensorChange_Handler(CPhidgetInterfaceKitHandle phid, int ( *fptr)(CPhidgetInterfaceKitHandle phid, void *userPtr, int index, int sensorValue), void *userPtr);
00265 int CPhidgetInterfaceKit_getSensorChangeTrigger(CPhidgetInterfaceKitHandle phid, int index, int *trigger);
00266 int CPhidgetInterfaceKit_setSensorChangeTrigger(CPhidgetInterfaceKitHandle phid, int index, int trigger);
00267 int CPhidgetInterfaceKit_getRatiometric(CPhidgetInterfaceKitHandle phid, int *ratiometric);
00268 int CPhidgetInterfaceKit_setRatiometric(CPhidgetInterfaceKitHandle phid, int ratiometric);
00269 int CPhidgetInterfaceKit_getDataRate(CPhidgetInterfaceKitHandle phid, int index, int *milliseconds);
00270 int CPhidgetInterfaceKit_setDataRate(CPhidgetInterfaceKitHandle phid, int index, int milliseconds);
00271 int CPhidgetInterfaceKit_getDataRateMax(CPhidgetInterfaceKitHandle phid, int index, int *max);
00272 int CPhidgetInterfaceKit_getDataRateMin(CPhidgetInterfaceKitHandle phid, int index, int *min);
00273 typedef struct _CPhidgetIR *CPhidgetIRHandle;
00274 int CPhidgetIR_create(CPhidgetIRHandle *phid);
00275 typedef enum {
00276 PHIDGET_IR_ENCODING_UNKNOWN = 1,
00277 PHIDGET_IR_ENCODING_SPACE,
00278 PHIDGET_IR_ENCODING_PULSE,
00279 PHIDGET_IR_ENCODING_BIPHASE,
00280 PHIDGET_IR_ENCODING_RC5,
00281 PHIDGET_IR_ENCODING_RC6
00282 } CPhidgetIR_Encoding;
00283 typedef enum {
00284 PHIDGET_IR_LENGTH_UNKNOWN = 1,
00285 PHIDGET_IR_LENGTH_CONSTANT,
00286 PHIDGET_IR_LENGTH_VARIABLE
00287 } CPhidgetIR_Length;
00288 typedef struct _CPhidgetIR_CodeInfo
00289 {
00290 int bitCount;
00291 CPhidgetIR_Encoding encoding;
00292 CPhidgetIR_Length length;
00293 int gap;
00294 int trail;
00295 int header[2];
00296 int one[2];
00297 int zero[2];
00298 int repeat[26];
00299 int min_repeat;
00300 unsigned char toggle_mask[(128 / 8)];
00301 int carrierFrequency;
00302 int dutyCycle;
00303 } CPhidgetIR_CodeInfo, *CPhidgetIR_CodeInfoHandle;
00304 int CPhidgetIR_Transmit(CPhidgetIRHandle phid, unsigned char *data, CPhidgetIR_CodeInfoHandle codeInfo);
00305 int CPhidgetIR_TransmitRepeat(CPhidgetIRHandle phid);
00306 int CPhidgetIR_TransmitRaw(CPhidgetIRHandle phid, int *data, int length, int carrierFrequency, int dutyCycle, int gap);
00307 int CPhidgetIR_getRawData(CPhidgetIRHandle phid, int *data, int *dataLength);
00308 int CPhidgetIR_getLastCode(CPhidgetIRHandle phid, unsigned char *data, int *dataLength, int *bitCount);
00309 int CPhidgetIR_getLastLearnedCode(CPhidgetIRHandle phid, unsigned char *data, int *dataLength, CPhidgetIR_CodeInfo *codeInfo);
00310 int CPhidgetIR_set_OnCode_Handler(CPhidgetIRHandle phid, int ( *fptr)(CPhidgetIRHandle phid, void *userPtr, unsigned char *data, int dataLength, int bitCount, int repeat), void *userPtr);
00311 int CPhidgetIR_set_OnLearn_Handler(CPhidgetIRHandle phid, int ( *fptr)(CPhidgetIRHandle phid, void *userPtr, unsigned char *data, int dataLength, CPhidgetIR_CodeInfoHandle codeInfo), void *userPtr);
00312 int CPhidgetIR_set_OnRawData_Handler(CPhidgetIRHandle phid, int ( *fptr)(CPhidgetIRHandle phid, void *userPtr, int *data, int dataLength), void *userPtr);
00313 typedef struct _CPhidgetLED *CPhidgetLEDHandle;
00314 int CPhidgetLED_create(CPhidgetLEDHandle *phid);
00315 typedef enum {
00316 PHIDGET_LED_CURRENT_LIMIT_20mA = 1,
00317 PHIDGET_LED_CURRENT_LIMIT_40mA,
00318 PHIDGET_LED_CURRENT_LIMIT_60mA,
00319 PHIDGET_LED_CURRENT_LIMIT_80mA
00320 } CPhidgetLED_CurrentLimit;
00321 typedef enum {
00322 PHIDGET_LED_VOLTAGE_1_7V = 1,
00323 PHIDGET_LED_VOLTAGE_2_75V,
00324 PHIDGET_LED_VOLTAGE_3_9V,
00325 PHIDGET_LED_VOLTAGE_5_0V
00326 } CPhidgetLED_Voltage;
00327 int CPhidgetLED_getLEDCount(CPhidgetLEDHandle phid, int *count);
00328 int CPhidgetLED_getDiscreteLED(CPhidgetLEDHandle phid, int index, int *brightness);
00329 int CPhidgetLED_setDiscreteLED(CPhidgetLEDHandle phid, int index, int brightness);
00330 int CPhidgetLED_getCurrentLimit(CPhidgetLEDHandle phid, CPhidgetLED_CurrentLimit *currentLimit);
00331 int CPhidgetLED_setCurrentLimit(CPhidgetLEDHandle phid, CPhidgetLED_CurrentLimit currentLimit);
00332 int CPhidgetLED_getVoltage(CPhidgetLEDHandle phid, CPhidgetLED_Voltage *voltage);
00333 int CPhidgetLED_setVoltage(CPhidgetLEDHandle phid, CPhidgetLED_Voltage voltage);
00334 typedef struct _CPhidgetMotorControl *CPhidgetMotorControlHandle;
00335 int CPhidgetMotorControl_create(CPhidgetMotorControlHandle *phid);
00336 int CPhidgetMotorControl_getMotorCount(CPhidgetMotorControlHandle phid, int *count);
00337 int CPhidgetMotorControl_getVelocity(CPhidgetMotorControlHandle phid, int index, double *velocity);
00338 int CPhidgetMotorControl_setVelocity(CPhidgetMotorControlHandle phid, int index, double velocity);
00339 int CPhidgetMotorControl_set_OnVelocityChange_Handler(CPhidgetMotorControlHandle phid, int ( *fptr)(CPhidgetMotorControlHandle phid, void *userPtr, int index, double velocity), void *userPtr);
00340 int CPhidgetMotorControl_getAcceleration(CPhidgetMotorControlHandle phid, int index, double *acceleration);
00341 int CPhidgetMotorControl_setAcceleration(CPhidgetMotorControlHandle phid, int index, double acceleration);
00342 int CPhidgetMotorControl_getAccelerationMax(CPhidgetMotorControlHandle phid, int index, double *max);
00343 int CPhidgetMotorControl_getAccelerationMin(CPhidgetMotorControlHandle phid, int index, double *min);
00344 int CPhidgetMotorControl_getCurrent(CPhidgetMotorControlHandle phid, int index, double *current);
00345 int CPhidgetMotorControl_set_OnCurrentChange_Handler(CPhidgetMotorControlHandle phid, int ( *fptr)(CPhidgetMotorControlHandle phid, void *userPtr, int index, double current), void *userPtr);
00346 int CPhidgetMotorControl_getInputCount(CPhidgetMotorControlHandle phid, int *count);
00347 int CPhidgetMotorControl_getInputState(CPhidgetMotorControlHandle phid, int index, int *inputState);
00348 int CPhidgetMotorControl_set_OnInputChange_Handler(CPhidgetMotorControlHandle phid, int ( *fptr)(CPhidgetMotorControlHandle phid, void *userPtr, int index, int inputState), void *userPtr);
00349 typedef struct _CPhidgetPHSensor *CPhidgetPHSensorHandle;
00350 int CPhidgetPHSensor_create(CPhidgetPHSensorHandle *phid);
00351 int CPhidgetPHSensor_getPH(CPhidgetPHSensorHandle phid, double *ph);
00352 int CPhidgetPHSensor_getPHMax(CPhidgetPHSensorHandle phid, double *max);
00353 int CPhidgetPHSensor_getPHMin(CPhidgetPHSensorHandle phid, double *min);
00354 int CPhidgetPHSensor_set_OnPHChange_Handler(CPhidgetPHSensorHandle phid, int ( *fptr)(CPhidgetPHSensorHandle phid, void *userPtr, double ph), void *userPtr);
00355 int CPhidgetPHSensor_getPHChangeTrigger(CPhidgetPHSensorHandle phid, double *trigger);
00356 int CPhidgetPHSensor_setPHChangeTrigger(CPhidgetPHSensorHandle phid, double trigger);
00357 int CPhidgetPHSensor_getPotential(CPhidgetPHSensorHandle phid, double *potential);
00358 int CPhidgetPHSensor_getPotentialMax(CPhidgetPHSensorHandle phid, double *max);
00359 int CPhidgetPHSensor_getPotentialMin(CPhidgetPHSensorHandle phid, double *min);
00360 int CPhidgetPHSensor_setTemperature(CPhidgetPHSensorHandle phid, double temperature);
00361 typedef struct _CPhidgetRFID *CPhidgetRFIDHandle;
00362 int CPhidgetRFID_create(CPhidgetRFIDHandle *phid);
00363 int CPhidgetRFID_getOutputCount(CPhidgetRFIDHandle phid, int *count);
00364 int CPhidgetRFID_getOutputState(CPhidgetRFIDHandle phid, int index, int *outputState);
00365 int CPhidgetRFID_setOutputState(CPhidgetRFIDHandle phid, int index, int outputState);
00366 int CPhidgetRFID_set_OnOutputChange_Handler(CPhidgetRFIDHandle phid, int ( *fptr)(CPhidgetRFIDHandle phid, void *userPtr, int index, int outputState), void *userPtr);
00367 int CPhidgetRFID_getAntennaOn(CPhidgetRFIDHandle phid, int *antennaState);
00368 int CPhidgetRFID_setAntennaOn(CPhidgetRFIDHandle phid, int antennaState);
00369 int CPhidgetRFID_getLEDOn(CPhidgetRFIDHandle phid, int *LEDState);
00370 int CPhidgetRFID_setLEDOn(CPhidgetRFIDHandle phid, int LEDState);
00371 int CPhidgetRFID_getLastTag(CPhidgetRFIDHandle phid, unsigned char *tag);
00372 int CPhidgetRFID_getTagStatus(CPhidgetRFIDHandle phid, int *status);
00373 int CPhidgetRFID_set_OnTag_Handler(CPhidgetRFIDHandle phid, int ( *fptr)(CPhidgetRFIDHandle phid, void *userPtr, unsigned char *tag), void *userPtr);
00374 int CPhidgetRFID_set_OnTagLost_Handler(CPhidgetRFIDHandle phid, int ( *fptr)(CPhidgetRFIDHandle phid, void *userPtr, unsigned char *tag), void *userPtr);
00375 typedef struct _CPhidgetServo *CPhidgetServoHandle;
00376 int CPhidgetServo_create(CPhidgetServoHandle *phid);
00377 int CPhidgetServo_getMotorCount(CPhidgetServoHandle phid, int *count);
00378 int CPhidgetServo_getPosition(CPhidgetServoHandle phid, int index, double *position);
00379 int CPhidgetServo_setPosition(CPhidgetServoHandle phid, int index, double position);
00380 int CPhidgetServo_getPositionMax(CPhidgetServoHandle phid, int index, double *max);
00381 int CPhidgetServo_getPositionMin(CPhidgetServoHandle phid, int index, double *min);
00382 int CPhidgetServo_set_OnPositionChange_Handler(CPhidgetServoHandle phid, int ( *fptr)(CPhidgetServoHandle phid, void *userPtr, int index, double position), void *userPtr);
00383 int CPhidgetServo_getEngaged(CPhidgetServoHandle phid, int index, int *engagedState);
00384 int CPhidgetServo_setEngaged(CPhidgetServoHandle phid, int index, int engagedState);
00385 int CPhidgetServo_getServoType(CPhidgetServoHandle phid, int index, CPhidget_ServoType *servoType);
00386 int CPhidgetServo_setServoType(CPhidgetServoHandle phid, int index, CPhidget_ServoType servoType);
00387 int CPhidgetServo_setServoParameters(CPhidgetServoHandle phid, int index, double min_us,double max_us,double degrees);
00388 typedef struct _CPhidgetSpatial *CPhidgetSpatialHandle;
00389 int CPhidgetSpatial_create(CPhidgetSpatialHandle *phid);
00390 typedef struct _CPhidgetSpatial_SpatialEventData
00391 {
00392 double acceleration[3];
00393 double angularRate[3];
00394 double magneticField[3];
00395 CPhidget_Timestamp timestamp;
00396 } CPhidgetSpatial_SpatialEventData, *CPhidgetSpatial_SpatialEventDataHandle;
00397 int CPhidgetSpatial_getAccelerationAxisCount(CPhidgetSpatialHandle phid, int *count);
00398 int CPhidgetSpatial_getGyroAxisCount(CPhidgetSpatialHandle phid, int *count);
00399 int CPhidgetSpatial_getCompassAxisCount(CPhidgetSpatialHandle phid, int *count);
00400 int CPhidgetSpatial_getAcceleration(CPhidgetSpatialHandle phid, int index, double *acceleration);
00401 int CPhidgetSpatial_getAccelerationMax(CPhidgetSpatialHandle phid, int index, double *max);
00402 int CPhidgetSpatial_getAccelerationMin(CPhidgetSpatialHandle phid, int index, double *min);
00403 int CPhidgetSpatial_getAngularRate(CPhidgetSpatialHandle phid, int index, double *angularRate);
00404 int CPhidgetSpatial_getAngularRateMax(CPhidgetSpatialHandle phid, int index, double *max);
00405 int CPhidgetSpatial_getAngularRateMin(CPhidgetSpatialHandle phid, int index, double *min);
00406 int CPhidgetSpatial_getMagneticField(CPhidgetSpatialHandle phid, int index, double *magneticField);
00407 int CPhidgetSpatial_getMagneticFieldMax(CPhidgetSpatialHandle phid, int index, double *max);
00408 int CPhidgetSpatial_getMagneticFieldMin(CPhidgetSpatialHandle phid, int index, double *min);
00409 int CPhidgetSpatial_zeroGyro(CPhidgetSpatialHandle phid);
00410 int CPhidgetSpatial_getDataRate(CPhidgetSpatialHandle phid, int *milliseconds);
00411 int CPhidgetSpatial_setDataRate(CPhidgetSpatialHandle phid, int milliseconds);
00412 int CPhidgetSpatial_getDataRateMax(CPhidgetSpatialHandle phid, int *max);
00413 int CPhidgetSpatial_getDataRateMin(CPhidgetSpatialHandle phid, int *min);
00414 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);
00415 int CPhidgetSpatial_resetCompassCorrectionParameters(CPhidgetSpatialHandle phid);
00416 int CPhidgetSpatial_set_OnSpatialData_Handler(CPhidgetSpatialHandle phid, int ( *fptr)(CPhidgetSpatialHandle phid, void *userPtr, CPhidgetSpatial_SpatialEventDataHandle *data, int dataCount), void *userPtr);
00417 typedef struct _CPhidgetStepper *CPhidgetStepperHandle;
00418 int CPhidgetStepper_create(CPhidgetStepperHandle *phid);
00419 int CPhidgetStepper_getInputCount(CPhidgetStepperHandle phid, int *count);
00420 int CPhidgetStepper_getInputState(CPhidgetStepperHandle phid, int index, int *inputState);
00421 int CPhidgetStepper_set_OnInputChange_Handler(CPhidgetStepperHandle phid, int ( *fptr)(CPhidgetStepperHandle phid, void *userPtr, int index, int inputState), void *userPtr);
00422 int CPhidgetStepper_getMotorCount(CPhidgetStepperHandle phid, int *count);
00423 int CPhidgetStepper_getAcceleration(CPhidgetStepperHandle phid, int index, double *acceleration);
00424 int CPhidgetStepper_setAcceleration(CPhidgetStepperHandle phid, int index, double acceleration);
00425 int CPhidgetStepper_getAccelerationMax(CPhidgetStepperHandle phid, int index, double *max);
00426 int CPhidgetStepper_getAccelerationMin(CPhidgetStepperHandle phid, int index, double *min);
00427 int CPhidgetStepper_getVelocityLimit(CPhidgetStepperHandle phid, int index, double *limit);
00428 int CPhidgetStepper_setVelocityLimit(CPhidgetStepperHandle phid, int index, double limit);
00429 int CPhidgetStepper_getVelocity(CPhidgetStepperHandle phid, int index, double *velocity);
00430 int CPhidgetStepper_getVelocityMax(CPhidgetStepperHandle phid, int index, double *max);
00431 int CPhidgetStepper_getVelocityMin(CPhidgetStepperHandle phid, int index, double *min);
00432 int CPhidgetStepper_set_OnVelocityChange_Handler(CPhidgetStepperHandle phid, int ( *fptr)(CPhidgetStepperHandle phid, void *userPtr, int index, double velocity), void *userPtr);
00433 int CPhidgetStepper_getTargetPosition(CPhidgetStepperHandle phid, int index, __int64 *position);
00434 int CPhidgetStepper_setTargetPosition(CPhidgetStepperHandle phid, int index, __int64 position);
00435 int CPhidgetStepper_getCurrentPosition(CPhidgetStepperHandle phid, int index, __int64 *position);
00436 int CPhidgetStepper_setCurrentPosition(CPhidgetStepperHandle phid, int index, __int64 position);
00437 int CPhidgetStepper_getPositionMax(CPhidgetStepperHandle phid, int index, __int64 *max);
00438 int CPhidgetStepper_getPositionMin(CPhidgetStepperHandle phid, int index, __int64 *min);
00439 int CPhidgetStepper_set_OnPositionChange_Handler(CPhidgetStepperHandle phid, int ( *fptr)(CPhidgetStepperHandle phid, void *userPtr, int index, __int64 position), void *userPtr);
00440 int CPhidgetStepper_getCurrentLimit(CPhidgetStepperHandle phid, int index, double *limit);
00441 int CPhidgetStepper_setCurrentLimit(CPhidgetStepperHandle phid, int index, double limit);
00442 int CPhidgetStepper_getCurrent(CPhidgetStepperHandle phid, int index, double *current);
00443 int CPhidgetStepper_getCurrentMax(CPhidgetStepperHandle phid, int index, double *max);
00444 int CPhidgetStepper_getCurrentMin(CPhidgetStepperHandle phid, int index, double *min);
00445 int CPhidgetStepper_set_OnCurrentChange_Handler(CPhidgetStepperHandle phid, int ( *fptr)(CPhidgetStepperHandle phid, void *userPtr, int index, double current), void *userPtr);
00446 int CPhidgetStepper_getEngaged(CPhidgetStepperHandle phid, int index, int *engagedState);
00447 int CPhidgetStepper_setEngaged(CPhidgetStepperHandle phid, int index, int engagedState);
00448 int CPhidgetStepper_getStopped(CPhidgetStepperHandle phid, int index, int *stoppedState);
00449 typedef struct _CPhidgetTemperatureSensor *CPhidgetTemperatureSensorHandle;
00450 int CPhidgetTemperatureSensor_create(CPhidgetTemperatureSensorHandle *phid);
00451 typedef enum {
00452 PHIDGET_TEMPERATURE_SENSOR_K_TYPE = 1,
00453 PHIDGET_TEMPERATURE_SENSOR_J_TYPE,
00454 PHIDGET_TEMPERATURE_SENSOR_E_TYPE,
00455 PHIDGET_TEMPERATURE_SENSOR_T_TYPE
00456 } CPhidgetTemperatureSensor_ThermocoupleType;
00457 int CPhidgetTemperatureSensor_getTemperatureInputCount(CPhidgetTemperatureSensorHandle phid, int *count);
00458 int CPhidgetTemperatureSensor_getTemperature(CPhidgetTemperatureSensorHandle phid, int index, double *temperature);
00459 int CPhidgetTemperatureSensor_getTemperatureMax(CPhidgetTemperatureSensorHandle phid, int index, double *max);
00460 int CPhidgetTemperatureSensor_getTemperatureMin(CPhidgetTemperatureSensorHandle phid, int index, double *min);
00461 int CPhidgetTemperatureSensor_set_OnTemperatureChange_Handler(CPhidgetTemperatureSensorHandle phid, int ( *fptr)(CPhidgetTemperatureSensorHandle phid, void *userPtr, int index, double temperature), void *userPtr);
00462 int CPhidgetTemperatureSensor_getTemperatureChangeTrigger(CPhidgetTemperatureSensorHandle phid, int index, double *trigger);
00463 int CPhidgetTemperatureSensor_setTemperatureChangeTrigger(CPhidgetTemperatureSensorHandle phid, int index, double trigger);
00464 int CPhidgetTemperatureSensor_getPotential(CPhidgetTemperatureSensorHandle phid, int index, double *potential);
00465 int CPhidgetTemperatureSensor_getPotentialMax(CPhidgetTemperatureSensorHandle phid, int index, double *max);
00466 int CPhidgetTemperatureSensor_getPotentialMin(CPhidgetTemperatureSensorHandle phid, int index, double *min);
00467 int CPhidgetTemperatureSensor_getAmbientTemperature(CPhidgetTemperatureSensorHandle phid, double *ambient);
00468 int CPhidgetTemperatureSensor_getAmbientTemperatureMax(CPhidgetTemperatureSensorHandle phid, double *max);
00469 int CPhidgetTemperatureSensor_getAmbientTemperatureMin(CPhidgetTemperatureSensorHandle phid, double *min);
00470 int CPhidgetTemperatureSensor_getThermocoupleType(CPhidgetTemperatureSensorHandle phid, int index, CPhidgetTemperatureSensor_ThermocoupleType *type);
00471 int CPhidgetTemperatureSensor_setThermocoupleType(CPhidgetTemperatureSensorHandle phid, int index, CPhidgetTemperatureSensor_ThermocoupleType type);
00472 typedef struct _CPhidgetTextLCD *CPhidgetTextLCDHandle;
00473 int CPhidgetTextLCD_create(CPhidgetTextLCDHandle *phid);
00474 int CPhidgetTextLCD_getRowCount(CPhidgetTextLCDHandle phid, int *count);
00475 int CPhidgetTextLCD_getColumnCount(CPhidgetTextLCDHandle phid, int *count);
00476 int CPhidgetTextLCD_getBacklight(CPhidgetTextLCDHandle phid, int *backlightState);
00477 int CPhidgetTextLCD_setBacklight(CPhidgetTextLCDHandle phid, int backlightState);
00478 int CPhidgetTextLCD_getBrightness(CPhidgetTextLCDHandle phid, int *brightness);
00479 int CPhidgetTextLCD_setBrightness(CPhidgetTextLCDHandle phid, int brightness);
00480 int CPhidgetTextLCD_getContrast(CPhidgetTextLCDHandle phid, int *contrast);
00481 int CPhidgetTextLCD_setContrast(CPhidgetTextLCDHandle phid, int contrast);
00482 int CPhidgetTextLCD_getCursorOn(CPhidgetTextLCDHandle phid, int *cursorState);
00483 int CPhidgetTextLCD_setCursorOn(CPhidgetTextLCDHandle phid, int cursorState);
00484 int CPhidgetTextLCD_getCursorBlink(CPhidgetTextLCDHandle phid, int *cursorBlinkState);
00485 int CPhidgetTextLCD_setCursorBlink(CPhidgetTextLCDHandle phid, int cursorBlinkState);
00486 int CPhidgetTextLCD_setCustomCharacter(CPhidgetTextLCDHandle phid, int index, int var1,int var2);
00487 int CPhidgetTextLCD_setDisplayCharacter(CPhidgetTextLCDHandle phid, int index, int column,unsigned char character);
00488 int CPhidgetTextLCD_setDisplayString(CPhidgetTextLCDHandle phid, int index, char *displayString);
00489 typedef struct _CPhidgetTextLED *CPhidgetTextLEDHandle;
00490 int CPhidgetTextLED_create(CPhidgetTextLEDHandle *phid);
00491 int CPhidgetTextLED_getRowCount(CPhidgetTextLEDHandle phid, int *count);
00492 int CPhidgetTextLED_getColumnCount(CPhidgetTextLEDHandle phid, int *count);
00493 int CPhidgetTextLED_getBrightness(CPhidgetTextLEDHandle phid, int *brightness);
00494 int CPhidgetTextLED_setBrightness(CPhidgetTextLEDHandle phid, int brightness);
00495 int CPhidgetTextLED_setDisplayString(CPhidgetTextLEDHandle phid, int index, char *displayString);
00496 typedef struct _CPhidgetWeightSensor *CPhidgetWeightSensorHandle;
00497 int CPhidgetWeightSensor_create(CPhidgetWeightSensorHandle *phid);
00498 int CPhidgetWeightSensor_getWeight(CPhidgetWeightSensorHandle phid, double *weight);
00499 int CPhidgetWeightSensor_set_OnWeightChange_Handler(CPhidgetWeightSensorHandle phid, int ( *fptr)(CPhidgetWeightSensorHandle phid, void *userPtr, double weight), void *userPtr);
00500 int CPhidgetWeightSensor_getWeightChangeTrigger(CPhidgetWeightSensorHandle phid, double *trigger);
00501 int CPhidgetWeightSensor_setWeightChangeTrigger(CPhidgetWeightSensorHandle phid, double trigger);
00502 #ifndef CPHIDGET_CONSTANTS
00503 #define CPHIDGET_CONSTANTS
00504
00514 #define PHIDGET_ATTACHED 0x1
00515 #define PHIDGET_NOTATTACHED 0x0
00518 //Adding error codes: Update .NET, COM, Python, Java
00519
00523 #define PHIDGET_ERROR_CODE_COUNT 20
00524 #define EPHIDGET_OK 0
00525 #define EPHIDGET_NOTFOUND 1
00526 #define EPHIDGET_NOMEMORY 2
00527 #define EPHIDGET_UNEXPECTED 3
00528 #define EPHIDGET_INVALIDARG 4
00529 #define EPHIDGET_NOTATTACHED 5
00530 #define EPHIDGET_INTERRUPTED 6
00531 #define EPHIDGET_INVALID 7
00532 #define EPHIDGET_NETWORK 8
00533 #define EPHIDGET_UNKNOWNVAL 9
00534 #define EPHIDGET_BADPASSWORD 10
00535 #define EPHIDGET_UNSUPPORTED 11
00536 #define EPHIDGET_DUPLICATE 12
00537 #define EPHIDGET_TIMEOUT 13
00538 #define EPHIDGET_OUTOFBOUNDS 14
00539 #define EPHIDGET_EVENT 15
00540 #define EPHIDGET_NETWORK_NOTCONNECTED 16
00541 #define EPHIDGET_WRONGDEVICE 17
00542 #define EPHIDGET_CLOSED 18
00543 #define EPHIDGET_BADVERSION 19
00546 //Adding error codes: Update .NET, COM, Python, Java
00547
00551 #define EEPHIDGET_EVENT_ERROR(code) (0x8000 + code)
00552
00553
00554 #define EEPHIDGET_NETWORK EEPHIDGET_EVENT_ERROR(0x0001)
00555 #define EEPHIDGET_BADPASSWORD EEPHIDGET_EVENT_ERROR(0x0002)
00556 #define EEPHIDGET_BADVERSION EEPHIDGET_EVENT_ERROR(0x0003)
00558 //Errors streamed back from firmware
00559 #define EEPHIDGET_OVERRUN EEPHIDGET_EVENT_ERROR(0x1002)
00560 #define EEPHIDGET_PACKETLOST EEPHIDGET_EVENT_ERROR(0x1003)
00561 #define EEPHIDGET_WRAP EEPHIDGET_EVENT_ERROR(0x1004)
00562 #define EEPHIDGET_OVERTEMP EEPHIDGET_EVENT_ERROR(0x1005)
00563 #define EEPHIDGET_OVERCURRENT EEPHIDGET_EVENT_ERROR(0x1006)
00564 #define EEPHIDGET_OUTOFRANGE EEPHIDGET_EVENT_ERROR(0x1007)
00565 #define EEPHIDGET_BADPOWER EEPHIDGET_EVENT_ERROR(0x1008)
00573 #define PUNK_BOOL 0x02
00574 #define PUNK_SHRT 0x7FFF
00575 #define PUNK_INT 0x7FFFFFFF
00576 #define PUNK_INT64 0x7FFFFFFFFFFFFFFFLL
00577 #define PUNK_DBL 1e300
00578 #define PUNK_FLT 1e30
00581 #define PFALSE 0x00
00582 #define PTRUE 0x01
00586 #endif
00587
00588 #ifdef __cplusplus
00589 }
00590 #endif
00591 #endif