phidgets 0.1.3 → 1.0.0

Sign up to get free protection for your applications and to get access to all the features.
Files changed (146) hide show
  1. checksums.yaml +4 -4
  2. data/History.txt +3 -0
  3. data/README.rdoc +32 -43
  4. data/Rakefile +4 -2
  5. data/bin/phidget +18 -72
  6. data/ext/phidgets/extconf.rb +5 -8
  7. data/ext/phidgets/phidgets.c +708 -173
  8. data/ext/phidgets/phidgets.h +54 -35
  9. data/ext/phidgets/phidgets_accelerometer.c +193 -109
  10. data/ext/phidgets/phidgets_bldc_motor.c +529 -0
  11. data/ext/phidgets/phidgets_capacitive_touch.c +302 -0
  12. data/ext/phidgets/phidgets_common.c +570 -315
  13. data/ext/phidgets/phidgets_current_input.c +229 -0
  14. data/ext/phidgets/phidgets_dc_motor.c +562 -0
  15. data/ext/phidgets/phidgets_dictionary.c +154 -213
  16. data/ext/phidgets/phidgets_digital_input.c +127 -0
  17. data/ext/phidgets/phidgets_digital_output.c +288 -0
  18. data/ext/phidgets/phidgets_distance_sensor.c +295 -0
  19. data/ext/phidgets/phidgets_encoder.c +211 -192
  20. data/ext/phidgets/phidgets_frequency_counter.c +310 -177
  21. data/ext/phidgets/phidgets_gps.c +226 -164
  22. data/ext/phidgets/phidgets_gyroscope.c +195 -0
  23. data/ext/phidgets/phidgets_hub.c +39 -0
  24. data/ext/phidgets/phidgets_humidity_sensor.c +200 -0
  25. data/ext/phidgets/phidgets_ir.c +211 -171
  26. data/ext/phidgets/phidgets_lcd.c +512 -0
  27. data/ext/phidgets/phidgets_light_sensor.c +200 -0
  28. data/ext/phidgets/phidgets_log.c +263 -0
  29. data/ext/phidgets/phidgets_magnetometer.c +279 -0
  30. data/ext/phidgets/phidgets_manager.c +86 -297
  31. data/ext/phidgets/phidgets_motor_position_controller.c +787 -0
  32. data/ext/phidgets/phidgets_phsensor.c +200 -152
  33. data/ext/phidgets/phidgets_power_guard.c +144 -0
  34. data/ext/phidgets/phidgets_pressure_sensor.c +200 -0
  35. data/ext/phidgets/phidgets_rc_servo.c +672 -0
  36. data/ext/phidgets/phidgets_resistance_input.c +227 -0
  37. data/ext/phidgets/phidgets_rfid.c +107 -221
  38. data/ext/phidgets/phidgets_sound_sensor.c +284 -0
  39. data/ext/phidgets/phidgets_spatial.c +124 -318
  40. data/ext/phidgets/phidgets_stepper.c +457 -430
  41. data/ext/phidgets/phidgets_temp_sensor.c +223 -228
  42. data/ext/phidgets/phidgets_voltage_input.c +428 -0
  43. data/ext/phidgets/phidgets_voltage_output.c +167 -0
  44. data/ext/phidgets/phidgets_voltage_ratio_input.c +435 -0
  45. data/lib/phidgets.rb +21 -14
  46. data/lib/phidgets/accelerometer.rb +11 -15
  47. data/lib/phidgets/bldc_motor.rb +45 -0
  48. data/lib/phidgets/capacitive_touch.rb +33 -0
  49. data/lib/phidgets/common.rb +40 -69
  50. data/lib/phidgets/current_input.rb +21 -0
  51. data/lib/phidgets/dc_motor.rb +45 -0
  52. data/lib/phidgets/dictionary.rb +30 -39
  53. data/lib/phidgets/digital_input.rb +21 -0
  54. data/lib/phidgets/digital_output.rb +56 -0
  55. data/lib/phidgets/distance_sensor.rb +33 -0
  56. data/lib/phidgets/encoder.rb +1 -29
  57. data/lib/phidgets/frequency_counter.rb +23 -14
  58. data/lib/phidgets/gps.rb +34 -26
  59. data/lib/phidgets/gyroscope.rb +21 -0
  60. data/lib/phidgets/humidity_sensor.rb +21 -0
  61. data/lib/phidgets/ir.rb +34 -39
  62. data/lib/phidgets/light_sensor.rb +21 -0
  63. data/lib/phidgets/magnetometer.rb +21 -0
  64. data/lib/phidgets/manager.rb +18 -66
  65. data/lib/phidgets/motor_position_controller.rb +45 -0
  66. data/lib/phidgets/ph_sensor.rb +2 -6
  67. data/lib/phidgets/pressure_sensor.rb +21 -0
  68. data/lib/phidgets/rc_servo.rb +58 -0
  69. data/lib/phidgets/resistance_input.rb +21 -0
  70. data/lib/phidgets/rfid.rb +22 -38
  71. data/lib/phidgets/sound_sensor.rb +21 -0
  72. data/lib/phidgets/spatial.rb +11 -15
  73. data/lib/phidgets/stepper.rb +48 -50
  74. data/lib/phidgets/temperature_sensor.rb +11 -15
  75. data/lib/phidgets/version.rb +5 -0
  76. data/lib/phidgets/voltage_input.rb +34 -0
  77. data/lib/phidgets/voltage_output.rb +23 -0
  78. data/lib/phidgets/voltage_ratio_input.rb +34 -0
  79. data/phidgets.gemspec +3 -22
  80. data/test/test_accelerometer.rb +42 -23
  81. data/test/test_bldc_motor.rb +134 -0
  82. data/test/test_capacitive_touch.rb +82 -0
  83. data/test/test_common.rb +125 -108
  84. data/test/test_current_input.rb +62 -0
  85. data/test/test_dc_motor.rb +146 -0
  86. data/test/test_dictionary.rb +22 -54
  87. data/test/test_digital_input.rb +30 -0
  88. data/test/test_digital_output.rb +70 -0
  89. data/test/test_distance_sensor.rb +76 -0
  90. data/test/test_encoder.rb +45 -38
  91. data/test/test_frequency_counter.rb +71 -36
  92. data/test/test_gps.rb +29 -38
  93. data/test/test_gyroscope.rb +54 -0
  94. data/test/test_helper.rb +0 -1
  95. data/test/test_hub.rb +14 -0
  96. data/test/test_humidity_sensor.rb +58 -0
  97. data/test/test_ir.rb +34 -34
  98. data/test/test_lcd.rb +146 -0
  99. data/test/test_light_sensor.rb +58 -0
  100. data/test/test_magnetometer.rb +78 -0
  101. data/test/test_manager.rb +10 -79
  102. data/test/test_motor_control.rb +146 -108
  103. data/test/test_phidgets.rb +2 -14
  104. data/test/test_phsensor.rb +46 -34
  105. data/test/test_power_guard.rb +42 -0
  106. data/test/test_pressure_sensor.rb +58 -0
  107. data/test/test_rc_servo.rb +174 -0
  108. data/test/test_resistance_input.rb +66 -0
  109. data/test/test_rfid.rb +15 -54
  110. data/test/test_sound_sensor.rb +78 -0
  111. data/test/test_spatial.rb +19 -85
  112. data/test/test_stepper.rb +89 -98
  113. data/test/test_temp_sensor.rb +42 -47
  114. data/test/test_voltage_input.rb +102 -0
  115. data/test/test_voltage_output.rb +46 -0
  116. data/test/test_voltage_ratio_input.rb +102 -0
  117. metadata +72 -89
  118. data/ext/phidgets/phidgets_advanced_servo.c +0 -567
  119. data/ext/phidgets/phidgets_analog.c +0 -139
  120. data/ext/phidgets/phidgets_bridge.c +0 -263
  121. data/ext/phidgets/phidgets_interface_kit.c +0 -340
  122. data/ext/phidgets/phidgets_led.c +0 -178
  123. data/ext/phidgets/phidgets_motor_control.c +0 -642
  124. data/ext/phidgets/phidgets_servo.c +0 -276
  125. data/ext/phidgets/phidgets_text_lcd.c +0 -381
  126. data/ext/phidgets/phidgets_text_led.c +0 -107
  127. data/ext/phidgets/phidgets_weight_sensor.c +0 -113
  128. data/lib/phidgets/advanced_servo.rb +0 -49
  129. data/lib/phidgets/analog.rb +0 -8
  130. data/lib/phidgets/bridge.rb +0 -25
  131. data/lib/phidgets/interfacekit.rb +0 -49
  132. data/lib/phidgets/led.rb +0 -8
  133. data/lib/phidgets/motor_control.rb +0 -110
  134. data/lib/phidgets/servo.rb +0 -23
  135. data/lib/phidgets/text_lcd.rb +0 -8
  136. data/lib/phidgets/text_led.rb +0 -8
  137. data/lib/phidgets/weight_sensor.rb +0 -25
  138. data/test/test_advanced_servo.rb +0 -152
  139. data/test/test_analog.rb +0 -45
  140. data/test/test_bridge.rb +0 -77
  141. data/test/test_interfacekit.rb +0 -97
  142. data/test/test_led.rb +0 -55
  143. data/test/test_servo.rb +0 -67
  144. data/test/test_text_lcd.rb +0 -115
  145. data/test/test_text_led.rb +0 -35
  146. data/test/test_weight_sensor.rb +0 -32
@@ -3,85 +3,104 @@
3
3
  #include <math.h>
4
4
  #include <time.h>
5
5
  #include <unistd.h>
6
+ #include <semaphore.h>
6
7
 
7
8
  #include <ruby.h>
8
- #include <phidget21.h>
9
+ #include <phidget22.h>
9
10
 
10
11
  #ifndef _PHIDGETS_EXT_
11
12
  #define _PHIDGETS_EXT_
12
13
 
13
14
 
14
15
  #define PH_CALLBACK_POLLING_INTERVAL 100000
15
- #define EPHIDGET_NOTIMPLEMENTED PHIDGET_ERROR_CODE_COUNT
16
+ #define EPHIDGET_NOTIMPLEMENTED 0x5000
16
17
 
17
18
 
18
- #ifdef PH_CALLBACK
19
19
  typedef struct ph_callback_data {
20
- volatile bool called;
20
+ sem_t handler_ready;
21
+ sem_t callback_called;
21
22
  volatile bool exit;
22
23
  VALUE phidget;
23
24
  VALUE callback;
25
+ VALUE arg1;
26
+ VALUE arg2;
27
+ VALUE arg3;
28
+ VALUE arg4;
24
29
  } ph_callback_data_t;
25
30
 
26
31
  void ph_callback_thread(ph_callback_data_t *callback_data);
27
- #if defined(HAVE_RB_THREAD_CALL_WITHOUT_GVL)
28
- typedef void * ph_callback_return_t;
29
- #else
30
- typedef VALUE ph_callback_return_t;
31
- #endif
32
- ph_callback_return_t wait_for_callback(void *arg);
32
+ void *wait_for_callback(void *arg);
33
33
  void cancel_wait_for_callback(void *arg);
34
- #endif
35
34
 
36
35
 
37
36
  typedef struct ph_data {
38
- CPhidgetHandle handle;
39
- #ifdef PH_CALLBACK
37
+ PhidgetHandle handle;
40
38
  ph_callback_data_t attach_callback;
41
39
  ph_callback_data_t detach_callback;
42
- ph_callback_data_t server_connect_callback;
43
- ph_callback_data_t server_disconnect_callback;
44
- ph_callback_data_t dev_callback_1;
45
- ph_callback_data_t dev_callback_2;
46
- ph_callback_data_t dev_callback_3;
47
- ph_callback_data_t dev_callback_4;
48
- ph_callback_data_t dev_callback_5;
49
- ph_callback_data_t dev_callback_6;
50
- ph_callback_data_t dev_callback_7;
51
- ph_callback_data_t dev_callback_8;
52
- #endif
40
+ ph_callback_data_t error_callback;
41
+ ph_callback_data_t property_change_callback;
42
+ ph_callback_data_t dev_callbacks[4];
53
43
  } ph_data_t;
54
44
 
55
45
 
56
46
  void Init_phidgets();
47
+ void Init_logging();
57
48
  void Init_dictionary();
58
49
  void Init_manager();
59
50
  void Init_common();
60
51
  void Init_accelerometer();
61
- void Init_advanced_servo();
62
- void Init_analog();
63
- void Init_bridge();
52
+ void Init_bldc_motor();
53
+ void Init_capacitive_touch();
54
+ void Init_current_input();
55
+ void Init_dc_motor();
56
+ void Init_digital_input();
57
+ void Init_digital_output();
58
+ void Init_distance();
64
59
  void Init_encoder();
65
60
  void Init_frequency_counter();
66
61
  void Init_gps();
67
- void Init_interface_kit();
62
+ void Init_gyroscope();
63
+ void Init_hub();
64
+ void Init_humidity();
68
65
  void Init_ir();
69
- void Init_led();
70
- void Init_motor_control();
66
+ void Init_lcd();
67
+ void Init_light();
68
+ void Init_magnetometer();
69
+ void Init_motor_position_controller();
71
70
  void Init_ph_sensor();
71
+ void Init_power_guard();
72
+ void Init_pressure();
73
+ void Init_rc_servo();
72
74
  void Init_rfid();
73
- void Init_servo();
75
+ void Init_resistance();
76
+ void Init_sound();
74
77
  void Init_spatial();
75
78
  void Init_stepper();
76
79
  void Init_temperature_sensor();
77
- void Init_text_lcd();
78
- void Init_text_led();
79
- void Init_weight_sensor();
80
+ void Init_voltage_input();
81
+ void Init_voltage_output();
82
+ void Init_voltage_ratio_input();
80
83
 
81
84
 
82
85
  ph_data_t *get_ph_data(VALUE self);
83
- CPhidgetHandle get_ph_handle(VALUE self);
86
+ PhidgetHandle get_ph_handle(VALUE self);
84
87
  void ph_raise(int err_code);
85
88
 
89
+ typedef PhidgetReturnCode (*phidget_get_int_func)(PhidgetHandle, int *);
90
+ typedef PhidgetReturnCode (*phidget_get_uint_func)(PhidgetHandle, uint32_t *);
91
+ typedef PhidgetReturnCode (*phidget_get_int64_func)(PhidgetHandle, int64_t *);
92
+ typedef PhidgetReturnCode (*phidget_get_uint64_func)(PhidgetHandle, uint64_t *);
93
+ typedef PhidgetReturnCode (*phidget_get_bool_func)(PhidgetHandle, int *);
94
+ typedef PhidgetReturnCode (*phidget_get_double_func)(PhidgetHandle, double *);
95
+ typedef PhidgetReturnCode (*phidget_get_string_func)(PhidgetHandle, const char **);
96
+
97
+ VALUE ph_get_int(PhidgetHandle handle, phidget_get_int_func func);
98
+ VALUE ph_get_uint(PhidgetHandle handle, phidget_get_uint_func func);
99
+ VALUE ph_get_int64(PhidgetHandle handle, phidget_get_int64_func func);
100
+ VALUE ph_get_uint64(PhidgetHandle handle, phidget_get_uint64_func func);
101
+ VALUE ph_get_bool(PhidgetHandle handle, phidget_get_bool_func func);
102
+ VALUE ph_get_double(PhidgetHandle handle, phidget_get_double_func func);
103
+ VALUE ph_get_string(PhidgetHandle handle, phidget_get_string_func func);
104
+
86
105
  #endif
87
106
 
@@ -1,165 +1,249 @@
1
1
 
2
2
  #include "phidgets.h"
3
3
 
4
+ #define ACCELEROMETER_ACCELERATION_CHANGE_CALLBACK 0
4
5
 
5
- VALUE ph_accel_init(VALUE self);
6
- VALUE ph_accel_get_axis_count(VALUE self);
7
- VALUE ph_accel_get_acceleration(VALUE self, VALUE index);
8
- VALUE ph_accel_get_acceleration_min(VALUE self, VALUE index);
9
- VALUE ph_accel_get_acceleration_max(VALUE self, VALUE index);
10
- VALUE ph_accel_get_acceleration_change_trigger(VALUE self, VALUE index);
11
- VALUE ph_accel_set_acceleration_change_trigger(VALUE self, VALUE index, VALUE trigger);
12
6
 
13
- #ifdef PH_CALLBACK
14
- VALUE ph_accel_set_on_acceleration_change_handler(VALUE self, VALUE handler);
15
- int ph_accel_on_acceleration_change(CPhidgetAccelerometerHandle phid, void *userPtr, int index, double accel);
16
- #endif
7
+ VALUE ph_accel_init(VALUE self) {
8
+ ph_data_t *ph = get_ph_data(self);
9
+ ph_raise(PhidgetAccelerometer_create((PhidgetAccelerometerHandle *)(&(ph->handle))));
10
+ return self;
11
+ }
17
12
 
18
13
 
14
+ VALUE ph_accel_get_axis_count(VALUE self) {
15
+ return ph_get_int(get_ph_handle(self), (phidget_get_int_func)PhidgetAccelerometer_getAxisCount);
16
+ }
19
17
 
20
- void Init_accelerometer() {
21
- VALUE ph_module = rb_const_get(rb_cObject, rb_intern("Phidgets"));
22
- VALUE ph_common = rb_const_get(ph_module, rb_intern("Common"));
23
- VALUE ph_accel = rb_define_class_under(ph_module, "Accelerometer", ph_common);
24
18
 
25
- /* Document-method: new
26
- * call-seq: new
27
- *
28
- * Creates a Phidget Accelerometer object.
29
- */
30
- rb_define_method(ph_accel, "initialize", ph_accel_init, 0);
19
+ VALUE ph_accel_get_acceleration(VALUE self) {
20
+ double accel[3];
21
+ ph_raise(PhidgetAccelerometer_getAcceleration((PhidgetAccelerometerHandle)get_ph_handle(self), &accel));
22
+ return rb_ary_new3(3, DBL2NUM(accel[0]), DBL2NUM(accel[1]), DBL2NUM(accel[2]));
23
+ }
31
24
 
32
- /* Document-method: getAxisCount
33
- * call-seq: getAxisCount
34
- *
35
- * Gets the number of acceleration axes supported by this accelerometer.
36
- */
37
- rb_define_method(ph_accel, "getAxisCount", ph_accel_get_axis_count, 0);
38
25
 
39
- /* Document-method: getAcceleration
40
- * call-seq: getAcceleration(index)
41
- *
42
- * Gets the current acceleration of an axis.
43
- */
44
- rb_define_method(ph_accel, "getAcceleration", ph_accel_get_acceleration, 1);
26
+ VALUE ph_accel_get_min_acceleration(VALUE self) {
27
+ double accel[3];
28
+ ph_raise(PhidgetAccelerometer_getMinAcceleration((PhidgetAccelerometerHandle)get_ph_handle(self), &accel));
29
+ return rb_ary_new3(3, DBL2NUM(accel[0]), DBL2NUM(accel[1]), DBL2NUM(accel[2]));
30
+ }
45
31
 
46
- /* Document-method: getAccelerationMin
47
- * call-seq: getAccelerationMin(index)
48
- *
49
- * Gets the minimum acceleraiton supported by an axis.
50
- */
51
- rb_define_method(ph_accel, "getAccelerationMin", ph_accel_get_acceleration_min, 1);
52
32
 
53
- /* Document-method: getAccelerationMax
54
- * call-seq: getAccelerationMax(index)
55
- *
56
- * Gets the maximum accleration supported by an axis.
57
- */
58
- rb_define_method(ph_accel, "getAccelerationMax", ph_accel_get_acceleration_max, 1);
33
+ VALUE ph_accel_get_max_acceleration(VALUE self) {
34
+ double accel[3];
35
+ ph_raise(PhidgetAccelerometer_getMaxAcceleration((PhidgetAccelerometerHandle)get_ph_handle(self), &accel));
36
+ return rb_ary_new3(3, DBL2NUM(accel[0]), DBL2NUM(accel[1]), DBL2NUM(accel[2]));
37
+ }
59
38
 
60
- /* Document-method: getAccelerationChangeTrigger
61
- * call-seq: getAccelerationChangeTrigger(index)
62
- *
63
- * Gets the change trigger for an axis.
64
- */
65
- rb_define_method(ph_accel, "getAccelerationChangeTrigger", ph_accel_get_acceleration_change_trigger, 1);
66
39
 
67
- /* Document-method: setAccelerationChangeTrigger
68
- * call-seq: setAccelerationChangeTrigger(index, trigger)
69
- *
70
- * Sets the change trigger for an axis.
71
- */
72
- rb_define_method(ph_accel, "setAccelerationChangeTrigger", ph_accel_set_acceleration_change_trigger, 2);
40
+ VALUE ph_accel_get_acceleration_change_trigger(VALUE self) {
41
+ return ph_get_double(get_ph_handle(self), (phidget_get_double_func)PhidgetAccelerometer_getAccelerationChangeTrigger);
42
+ }
73
43
 
74
- #ifdef PH_CALLBACK
75
- rb_define_private_method(ph_accel, "ext_setOnAccelerationChangeHandler", ph_accel_set_on_acceleration_change_handler, 1);
76
- #endif
77
44
 
78
- rb_define_alias(ph_accel, "axis_count", "getAxisCount");
79
- rb_define_alias(ph_accel, "acceleration", "getAcceleration");
80
- rb_define_alias(ph_accel, "acceleration_min", "getAccelerationMin");
81
- rb_define_alias(ph_accel, "acceleration_max", "getAccelerationMax");
82
- rb_define_alias(ph_accel, "acceleration_change_trigger", "getAccelerationChangeTrigger");
83
- rb_define_alias(ph_accel, "set_acceleration_change_trigger", "setAccelerationChangeTrigger");
45
+ VALUE ph_accel_set_acceleration_change_trigger(VALUE self, VALUE trigger) {
46
+ ph_raise(PhidgetAccelerometer_setAccelerationChangeTrigger((PhidgetAccelerometerHandle)get_ph_handle(self), NUM2DBL(trigger)));
47
+ return Qnil;
84
48
  }
85
49
 
86
50
 
87
- VALUE ph_accel_init(VALUE self) {
88
- ph_data_t *ph = get_ph_data(self);
89
- ph_raise(CPhidgetAccelerometer_create((CPhidgetAccelerometerHandle *)(&(ph->handle))));
90
- return self;
51
+ VALUE ph_accel_get_min_acceleration_change_trigger(VALUE self) {
52
+ return ph_get_double(get_ph_handle(self), (phidget_get_double_func)PhidgetAccelerometer_getMinAccelerationChangeTrigger);
91
53
  }
92
54
 
93
55
 
94
- VALUE ph_accel_get_axis_count(VALUE self) {
95
- CPhidgetAccelerometerHandle handle = (CPhidgetAccelerometerHandle)get_ph_handle(self);
96
- int count;
97
- ph_raise(CPhidgetAccelerometer_getAxisCount(handle, &count));
98
- return INT2FIX(count);
56
+ VALUE ph_accel_get_max_acceleration_change_trigger(VALUE self) {
57
+ return ph_get_double(get_ph_handle(self), (phidget_get_double_func)PhidgetAccelerometer_getMaxAccelerationChangeTrigger);
99
58
  }
100
59
 
101
60
 
102
- VALUE ph_accel_get_acceleration(VALUE self, VALUE index) {
103
- CPhidgetAccelerometerHandle handle = (CPhidgetAccelerometerHandle)get_ph_handle(self);
104
- double accel;
105
- ph_raise(CPhidgetAccelerometer_getAcceleration(handle, NUM2INT(index), &accel));
106
- return rb_float_new(accel);
61
+ VALUE ph_accel_get_data_interval(VALUE self) {
62
+ return ph_get_uint(get_ph_handle(self), (phidget_get_uint_func)PhidgetAccelerometer_getDataInterval);
107
63
  }
108
64
 
109
65
 
110
- VALUE ph_accel_get_acceleration_min(VALUE self, VALUE index) {
111
- CPhidgetAccelerometerHandle handle = (CPhidgetAccelerometerHandle)get_ph_handle(self);
112
- double accel;
113
- ph_raise(CPhidgetAccelerometer_getAccelerationMin(handle, NUM2INT(index), &accel));
114
- return rb_float_new(accel);
66
+ VALUE ph_accel_set_data_interval(VALUE self, VALUE interval) {
67
+ ph_raise(PhidgetAccelerometer_setDataInterval((PhidgetAccelerometerHandle)get_ph_handle(self), NUM2UINT(interval)));
68
+ return Qnil;
115
69
  }
116
70
 
117
71
 
118
- VALUE ph_accel_get_acceleration_max(VALUE self, VALUE index) {
119
- CPhidgetAccelerometerHandle handle = (CPhidgetAccelerometerHandle)get_ph_handle(self);
120
- double accel;
121
- ph_raise(CPhidgetAccelerometer_getAccelerationMax(handle, NUM2INT(index), &accel));
122
- return rb_float_new(accel);
72
+ VALUE ph_accel_get_min_data_interval(VALUE self) {
73
+ return ph_get_uint(get_ph_handle(self), (phidget_get_uint_func)PhidgetAccelerometer_getMinDataInterval);
123
74
  }
124
75
 
125
76
 
126
- VALUE ph_accel_get_acceleration_change_trigger(VALUE self, VALUE index) {
127
- CPhidgetAccelerometerHandle handle = (CPhidgetAccelerometerHandle)get_ph_handle(self);
128
- double trigger;
129
- ph_raise(CPhidgetAccelerometer_getAccelerationChangeTrigger(handle, NUM2INT(index), &trigger));
130
- return rb_float_new(trigger);
77
+ VALUE ph_accel_get_max_data_interval(VALUE self) {
78
+ return ph_get_uint(get_ph_handle(self), (phidget_get_uint_func)PhidgetAccelerometer_getMaxDataInterval);
131
79
  }
132
80
 
133
81
 
134
- VALUE ph_accel_set_acceleration_change_trigger(VALUE self, VALUE index, VALUE trigger) {
135
- CPhidgetAccelerometerHandle handle = (CPhidgetAccelerometerHandle)get_ph_handle(self);
136
- ph_raise(CPhidgetAccelerometer_setAccelerationChangeTrigger(handle, NUM2INT(index), NUM2DBL(trigger)));
137
- return Qnil;
82
+ VALUE ph_accel_get_timestamp(VALUE self) {
83
+ return ph_get_double(get_ph_handle(self), (phidget_get_double_func)PhidgetAccelerometer_getTimestamp);
84
+ }
85
+
86
+
87
+ void CCONV ph_accel_on_acceleration_change(PhidgetAccelerometerHandle phid, void *userPtr, const double accel[3], double timestamp) {
88
+ ph_callback_data_t *callback_data = ((ph_callback_data_t *)userPtr);
89
+ while(sem_wait(&callback_data->handler_ready)!=0) {};
90
+ callback_data->arg1 = rb_ary_new3(3, DBL2NUM(accel[0]), DBL2NUM(accel[1]), DBL2NUM(accel[2]));
91
+ callback_data->arg2 = DBL2NUM(timestamp);
92
+ callback_data->arg3 = Qnil;
93
+ callback_data->arg4 = Qnil;
94
+ sem_post(&callback_data->callback_called);
138
95
  }
139
96
 
140
- #ifdef PH_CALLBACK
97
+
141
98
  VALUE ph_accel_set_on_acceleration_change_handler(VALUE self, VALUE handler) {
142
99
  ph_data_t *ph = get_ph_data(self);
143
- ph_callback_data_t *callback_data = &ph->dev_callback_1;
100
+ ph_callback_data_t *callback_data = &ph->dev_callbacks[ACCELEROMETER_ACCELERATION_CHANGE_CALLBACK];
144
101
  if( TYPE(handler) == T_NIL ) {
102
+ callback_data->callback = T_NIL;
145
103
  callback_data->exit = true;
146
- ph_raise(CPhidgetAccelerometer_set_OnAccelerationChange_Handler((CPhidgetAccelerometerHandle)ph->handle, NULL, (void *)NULL));
104
+ ph_raise(PhidgetAccelerometer_setOnAccelerationChangeHandler((PhidgetAccelerometerHandle)ph->handle, NULL, (void *)NULL));
105
+ sem_post(&callback_data->callback_called);
147
106
  } else {
148
- callback_data->called = false;
149
107
  callback_data->exit = false;
150
108
  callback_data->phidget = self;
151
109
  callback_data->callback = handler;
152
- ph_raise(CPhidgetAccelerometer_set_OnAccelerationChange_Handler((CPhidgetAccelerometerHandle)ph->handle, ph_accel_on_acceleration_change, (void *)callback_data));
110
+ ph_raise(PhidgetAccelerometer_setOnAccelerationChangeHandler((PhidgetAccelerometerHandle)ph->handle, ph_accel_on_acceleration_change, (void *)callback_data));
153
111
  ph_callback_thread(callback_data);
154
112
  }
155
113
  return Qnil;
156
114
  }
157
115
 
158
116
 
159
- int ph_accel_on_acceleration_change(CPhidgetAccelerometerHandle phid, void *userPtr, int index, double accel) {
160
- ph_callback_data_t *callback_data = ((ph_callback_data_t *)userPtr);
161
- callback_data->called = true;
162
- return EPHIDGET_OK;
117
+
118
+ void Init_accelerometer() {
119
+ VALUE ph_module = rb_const_get(rb_cObject, rb_intern("Phidgets"));
120
+ VALUE ph_common = rb_const_get(ph_module, rb_intern("Common"));
121
+ VALUE ph_accel = rb_define_class_under(ph_module, "Accelerometer", ph_common);
122
+
123
+ /* Document-method: new
124
+ * call-seq: new
125
+ *
126
+ * Creates a Phidget Accelerometer object.
127
+ */
128
+ rb_define_method(ph_accel, "initialize", ph_accel_init, 0);
129
+
130
+ /* Document-method: getAxisCount
131
+ * call-seq: getAxisCount -> axis_count
132
+ *
133
+ * The number of axes the channel can measure acceleration on.
134
+ * See your device's User Guide for more information about the number of axes and their orientation.
135
+ */
136
+ rb_define_method(ph_accel, "getAxisCount", ph_accel_get_axis_count, 0);
137
+ rb_define_alias(ph_accel, "axis_count", "getAxisCount");
138
+
139
+ /* Document-method: getAcceleration
140
+ * call-seq: getAcceleration -> acceleration
141
+ *
142
+ * The most recent acceleration value that the channel has reported.
143
+ * This value will always be between MinAcceleration and MaxAcceleration.
144
+ */
145
+ rb_define_method(ph_accel, "getAcceleration", ph_accel_get_acceleration, 0);
146
+ rb_define_alias(ph_accel, "acceleration", "getAcceleration");
147
+
148
+ /* Document-method: getMinAcceleration
149
+ * call-seq: getMinAcceleration -> min_acceleration
150
+ *
151
+ * The minimum value the AccelerationChange event will report.
152
+ */
153
+ rb_define_method(ph_accel, "getMinAcceleration", ph_accel_get_min_acceleration, 0);
154
+ rb_define_alias(ph_accel, "min_acceleration", "getMinAcceleration");
155
+
156
+ /* Document-method: getMaxAcceleration
157
+ * call-seq: getMaxAcceleration -> max_acceleration
158
+ *
159
+ * The maximum value the AccelerationChange event will report.
160
+ */
161
+ rb_define_method(ph_accel, "getMaxAcceleration", ph_accel_get_max_acceleration, 0);
162
+ rb_define_alias(ph_accel, "max_acceleration", "getMaxAcceleration");
163
+
164
+ /* Document-method: getAccelerationChangeTrigger
165
+ * call-seq: getAccelerationChangeTrigger -> trigger
166
+ *
167
+ * The channel will not issue a AccelerationChange event until the acceleration value has changed
168
+ * by the amount specified by the AccelerationChangeTrigger.
169
+ * Setting the AccelerationChangeTrigger to 0 will result in the channel firing events every DataInterval.
170
+ * This is useful for applications that implement their own data filtering.
171
+ */
172
+ rb_define_method(ph_accel, "getAccelerationChangeTrigger", ph_accel_get_acceleration_change_trigger, 0);
173
+ rb_define_alias(ph_accel, "acceleration_change_trigger", "getAccelerationChangeTrigger");
174
+
175
+ /* Document-method: setAccelerationChangeTrigger
176
+ * call-seq: setAccelerationChangeTrigger(trigger)
177
+ *
178
+ * The channel will not issue a AccelerationChange event until the acceleration value has changed
179
+ * by the amount specified by the AccelerationChangeTrigger.
180
+ * Setting the AccelerationChangeTrigger to 0 will result in the channel firing events every DataInterval.
181
+ * This is useful for applications that implement their own data filtering.
182
+ */
183
+ rb_define_method(ph_accel, "setAccelerationChangeTrigger", ph_accel_set_acceleration_change_trigger, 1);
184
+ rb_define_alias(ph_accel, "acceleration_change_trigger=", "setAccelerationChangeTrigger");
185
+
186
+ /* Document-method: getMinAccelerationChangeTrigger
187
+ * call-seq: getMinAccelerationChangeTrigger -> trigger
188
+ *
189
+ * The minimum value that AccelerationChangeTrigger can be set to.
190
+ */
191
+ rb_define_method(ph_accel, "getMinAccelerationChangeTrigger", ph_accel_get_min_acceleration_change_trigger, 0);
192
+ rb_define_alias(ph_accel, "min_acceleration_change_trigger", "getMinAccelerationChangeTrigger");
193
+
194
+ /* Document-method: getMaxAccelerationChangeTrigger
195
+ * call-seq: getMaxAccelerationChangeTrigger -> trigger
196
+ *
197
+ * The maximum value that AccelerationChangeTrigger can be set to.
198
+ */
199
+ rb_define_method(ph_accel, "getMaxAccelerationChangeTrigger", ph_accel_get_max_acceleration_change_trigger, 0);
200
+ rb_define_alias(ph_accel, "max_acceleration_change_trigger", "getMaxAccelerationChangeTrigger");
201
+
202
+ /* Document-method: getDataInterval
203
+ * call-seq: getDataInterval -> interval
204
+ *
205
+ * The DataInterval is the time that must elapse before the channel will fire another Phidget_OnAccelerationChangeCallback event.
206
+ * The data interval is bounded by MinDataInterval and MaxDataInterval.
207
+ * The timing between AccelerationChange events can also be affected by the AccelerationChangeTrigger.
208
+ */
209
+ rb_define_method(ph_accel, "getDataInterval", ph_accel_get_data_interval, 0);
210
+ rb_define_alias(ph_accel, "data_interval", "getDataInterval");
211
+
212
+ /* Document-method: setDataInterval
213
+ * call-seq: setDataInterval(interval)
214
+ *
215
+ * The DataInterval is the time that must elapse before the channel will fire another Phidget_OnAccelerationChangeCallback event.
216
+ * The data interval is bounded by MinDataInterval and MaxDataInterval.
217
+ * The timing between AccelerationChange events can also be affected by the AccelerationChangeTrigger.
218
+ */
219
+ rb_define_method(ph_accel, "setDataInterval", ph_accel_set_data_interval, 1);
220
+ rb_define_alias(ph_accel, "data_interval=", "setDataInterval");
221
+
222
+ /* Document-method: getMinDataInterval
223
+ * call-seq: getMinDataInterval -> interval
224
+ *
225
+ * The minimum value that DataInterval can be set to.
226
+ */
227
+ rb_define_method(ph_accel, "getMinDataInterval", ph_accel_get_min_data_interval, 0);
228
+ rb_define_alias(ph_accel, "min_data_interval", "getMinDataInterval");
229
+
230
+ /* Document-method: getMaxDataInterval
231
+ * call-seq: getMaxDataInterval -> interval
232
+ *
233
+ * The maximum value that DataInterval can be set to.
234
+ */
235
+ rb_define_method(ph_accel, "getMaxDataInterval", ph_accel_get_max_data_interval, 0);
236
+ rb_define_alias(ph_accel, "max_data_interval", "getMaxDataInterval");
237
+
238
+ /* Document-method: getTimestamp
239
+ * call-seq: getTimestamp -> timestamp
240
+ *
241
+ * The most recent timestamp value that the channel has reported. This is an extremely accurate time measurement streamed from the device.
242
+ * If your application requires a time measurement, you should use this value over a local software timestamp.
243
+ */
244
+ rb_define_method(ph_accel, "getTimestamp", ph_accel_get_timestamp, 0);
245
+ rb_define_alias(ph_accel, "timestamp", "getTimestamp");
246
+
247
+ rb_define_private_method(ph_accel, "ext_setOnAccelerationChangeHandler", ph_accel_set_on_acceleration_change_handler, 1);
163
248
  }
164
- #endif
165
249