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