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
@@ -0,0 +1,787 @@
1
+
2
+ #include "phidgets.h"
3
+
4
+ #define MOTOR_DUTY_CYCLE_UPDATE_CALLBACK 0
5
+ #define MOTOR_POSITION_UPDATE_CALLBACK 1
6
+ #define MOTOR_TARGET_POSITION_ASYNC_CALLBACK 2
7
+
8
+
9
+
10
+ VALUE ph_motor_init(VALUE self) {
11
+ ph_data_t *ph = get_ph_data(self);
12
+ ph_raise(PhidgetMotorPositionController_create((PhidgetMotorPositionControllerHandle *)(&(ph->handle))));
13
+ return self;
14
+ }
15
+
16
+ VALUE ph_motor_get_acceleration(VALUE self) {
17
+ return ph_get_double(get_ph_handle(self), (phidget_get_double_func)PhidgetMotorPositionController_getAcceleration);
18
+ }
19
+
20
+ VALUE ph_motor_set_acceleration(VALUE self, VALUE accel) {
21
+ ph_raise(PhidgetMotorPositionController_setAcceleration((PhidgetMotorPositionControllerHandle)get_ph_handle(self), NUM2DBL(accel)));
22
+ return Qnil;
23
+ }
24
+
25
+ VALUE ph_motor_get_min_acceleration(VALUE self) {
26
+ return ph_get_double(get_ph_handle(self), (phidget_get_double_func)PhidgetMotorPositionController_getMinAcceleration);
27
+ }
28
+
29
+ VALUE ph_motor_get_max_acceleration(VALUE self) {
30
+ return ph_get_double(get_ph_handle(self), (phidget_get_double_func)PhidgetMotorPositionController_getMaxAcceleration);
31
+ }
32
+
33
+ VALUE ph_motor_get_current_limit(VALUE self) {
34
+ return ph_get_double(get_ph_handle(self), (phidget_get_double_func)PhidgetMotorPositionController_getCurrentLimit);
35
+ }
36
+
37
+ VALUE ph_motor_set_current_limit(VALUE self, VALUE current) {
38
+ ph_raise(PhidgetMotorPositionController_setCurrentLimit((PhidgetMotorPositionControllerHandle)get_ph_handle(self), NUM2DBL(current)));
39
+ return Qnil;
40
+ }
41
+
42
+ VALUE ph_motor_get_min_current_limit(VALUE self) {
43
+ return ph_get_double(get_ph_handle(self), (phidget_get_double_func)PhidgetMotorPositionController_getMinCurrentLimit);
44
+ }
45
+
46
+ VALUE ph_motor_get_max_current_limit(VALUE self) {
47
+ return ph_get_double(get_ph_handle(self), (phidget_get_double_func)PhidgetMotorPositionController_getMaxCurrentLimit);
48
+ }
49
+
50
+ VALUE ph_motor_get_current_regulator_gain(VALUE self) {
51
+ return ph_get_double(get_ph_handle(self), (phidget_get_double_func)PhidgetMotorPositionController_getCurrentRegulatorGain);
52
+ }
53
+
54
+ VALUE ph_motor_set_current_regulator_gain(VALUE self, VALUE gain) {
55
+ ph_raise(PhidgetMotorPositionController_setCurrentRegulatorGain((PhidgetMotorPositionControllerHandle)get_ph_handle(self), NUM2DBL(gain)));
56
+ return Qnil;
57
+ }
58
+
59
+ VALUE ph_motor_get_min_current_regulator_gain(VALUE self) {
60
+ return ph_get_double(get_ph_handle(self), (phidget_get_double_func)PhidgetMotorPositionController_getMinCurrentRegulatorGain);
61
+ }
62
+
63
+ VALUE ph_motor_get_max_current_regulator_gain(VALUE self) {
64
+ return ph_get_double(get_ph_handle(self), (phidget_get_double_func)PhidgetMotorPositionController_getMaxCurrentRegulatorGain);
65
+ }
66
+
67
+ VALUE ph_motor_get_data_interval(VALUE self) {
68
+ return ph_get_uint(get_ph_handle(self), (phidget_get_uint_func)PhidgetMotorPositionController_getDataInterval);
69
+ }
70
+
71
+ VALUE ph_motor_set_data_interval(VALUE self, VALUE interval) {
72
+ ph_raise(PhidgetMotorPositionController_setDataInterval((PhidgetMotorPositionControllerHandle)get_ph_handle(self), NUM2UINT(interval)));
73
+ return Qnil;
74
+ }
75
+
76
+ VALUE ph_motor_get_min_data_interval(VALUE self) {
77
+ return ph_get_uint(get_ph_handle(self), (phidget_get_uint_func)PhidgetMotorPositionController_getMinDataInterval);
78
+ }
79
+
80
+ VALUE ph_motor_get_max_data_interval(VALUE self) {
81
+ return ph_get_uint(get_ph_handle(self), (phidget_get_uint_func)PhidgetMotorPositionController_getMaxDataInterval);
82
+ }
83
+
84
+ VALUE ph_motor_get_dead_band(VALUE self) {
85
+ return ph_get_double(get_ph_handle(self), (phidget_get_double_func)PhidgetMotorPositionController_getDeadBand);
86
+ }
87
+
88
+ VALUE ph_motor_set_dead_band(VALUE self, VALUE dead_band) {
89
+ ph_raise(PhidgetMotorPositionController_setDeadBand((PhidgetMotorPositionControllerHandle)get_ph_handle(self), NUM2DBL(dead_band)));
90
+ return Qnil;
91
+ }
92
+
93
+ VALUE ph_motor_get_duty_cycle(VALUE self) {
94
+ return ph_get_double(get_ph_handle(self), (phidget_get_double_func)PhidgetMotorPositionController_getDutyCycle);
95
+ }
96
+
97
+ VALUE ph_motor_get_engaged(VALUE self) {
98
+ return ph_get_bool(get_ph_handle(self), (phidget_get_bool_func)PhidgetMotorPositionController_getEngaged);
99
+ }
100
+
101
+ VALUE ph_motor_set_engaged(VALUE self, VALUE engaged) {
102
+ ph_raise(PhidgetMotorPositionController_setEngaged((PhidgetMotorPositionControllerHandle)get_ph_handle(self), TYPE(engaged) == T_TRUE ? PTRUE : PFALSE));
103
+ return Qnil;
104
+ }
105
+
106
+ VALUE ph_motor_get_fan_mode(VALUE self) {
107
+ return ph_get_int(get_ph_handle(self), (phidget_get_int_func)PhidgetMotorPositionController_getFanMode);
108
+ }
109
+
110
+ VALUE ph_motor_set_fan_mode(VALUE self, VALUE fan_mode) {
111
+ ph_raise(PhidgetMotorPositionController_setFanMode((PhidgetMotorPositionControllerHandle)get_ph_handle(self), NUM2INT(fan_mode)));
112
+ return Qnil;
113
+ }
114
+
115
+ VALUE ph_motor_get_io_mode(VALUE self) {
116
+ return ph_get_int(get_ph_handle(self), (phidget_get_int_func)PhidgetMotorPositionController_getIOMode);
117
+ }
118
+
119
+ VALUE ph_motor_set_io_mode(VALUE self, VALUE io_mode) {
120
+ ph_raise(PhidgetMotorPositionController_setIOMode((PhidgetMotorPositionControllerHandle)get_ph_handle(self), NUM2INT(io_mode)));
121
+ return Qnil;
122
+ }
123
+
124
+ VALUE ph_motor_get_kd(VALUE self) {
125
+ return ph_get_double(get_ph_handle(self), (phidget_get_double_func)PhidgetMotorPositionController_getKd);
126
+ }
127
+
128
+ VALUE ph_motor_set_kd(VALUE self, VALUE kd) {
129
+ ph_raise(PhidgetMotorPositionController_setKd((PhidgetMotorPositionControllerHandle)get_ph_handle(self), NUM2DBL(kd)));
130
+ return Qnil;
131
+ }
132
+
133
+ VALUE ph_motor_get_ki(VALUE self) {
134
+ return ph_get_double(get_ph_handle(self), (phidget_get_double_func)PhidgetMotorPositionController_getKi);
135
+ }
136
+
137
+ VALUE ph_motor_set_ki(VALUE self, VALUE ki) {
138
+ ph_raise(PhidgetMotorPositionController_setKi((PhidgetMotorPositionControllerHandle)get_ph_handle(self), NUM2DBL(ki)));
139
+ return Qnil;
140
+ }
141
+
142
+ VALUE ph_motor_get_kp(VALUE self) {
143
+ return ph_get_double(get_ph_handle(self), (phidget_get_double_func)PhidgetMotorPositionController_getKp);
144
+ }
145
+
146
+ VALUE ph_motor_set_kp(VALUE self, VALUE kp) {
147
+ ph_raise(PhidgetMotorPositionController_setKp((PhidgetMotorPositionControllerHandle)get_ph_handle(self), NUM2DBL(kp)));
148
+ return Qnil;
149
+ }
150
+
151
+ VALUE ph_motor_get_position(VALUE self) {
152
+ return ph_get_double(get_ph_handle(self), (phidget_get_double_func)PhidgetMotorPositionController_getPosition);
153
+ }
154
+
155
+ VALUE ph_motor_get_min_position(VALUE self) {
156
+ return ph_get_double(get_ph_handle(self), (phidget_get_double_func)PhidgetMotorPositionController_getMinPosition);
157
+ }
158
+
159
+ VALUE ph_motor_get_max_position(VALUE self) {
160
+ return ph_get_double(get_ph_handle(self), (phidget_get_double_func)PhidgetMotorPositionController_getMaxPosition);
161
+ }
162
+
163
+ VALUE ph_motor_add_position_offset(VALUE self, VALUE offset) {
164
+ ph_raise(PhidgetMotorPositionController_addPositionOffset((PhidgetMotorPositionControllerHandle)get_ph_handle(self), NUM2DBL(offset)));
165
+ return Qnil;
166
+ }
167
+
168
+ VALUE ph_motor_get_rescale_factor(VALUE self) {
169
+ return ph_get_double(get_ph_handle(self), (phidget_get_double_func)PhidgetMotorPositionController_getRescaleFactor);
170
+ }
171
+
172
+ VALUE ph_motor_set_rescale_factor(VALUE self, VALUE rescale_factor) {
173
+ ph_raise(PhidgetMotorPositionController_setRescaleFactor((PhidgetMotorPositionControllerHandle)get_ph_handle(self), NUM2DBL(rescale_factor)));
174
+ return Qnil;
175
+ }
176
+
177
+ VALUE ph_motor_get_stall_velocity(VALUE self) {
178
+ return ph_get_double(get_ph_handle(self), (phidget_get_double_func)PhidgetMotorPositionController_getStallVelocity);
179
+ }
180
+
181
+ VALUE ph_motor_set_stall_velocity(VALUE self, VALUE stall_velocity) {
182
+ ph_raise(PhidgetMotorPositionController_setStallVelocity((PhidgetMotorPositionControllerHandle)get_ph_handle(self), NUM2DBL(stall_velocity)));
183
+ return Qnil;
184
+ }
185
+
186
+ VALUE ph_motor_get_min_stall_velocity(VALUE self) {
187
+ return ph_get_double(get_ph_handle(self), (phidget_get_double_func)PhidgetMotorPositionController_getMinStallVelocity);
188
+ }
189
+
190
+ VALUE ph_motor_get_max_stall_velocity(VALUE self) {
191
+ return ph_get_double(get_ph_handle(self), (phidget_get_double_func)PhidgetMotorPositionController_getMaxStallVelocity);
192
+ }
193
+
194
+ VALUE ph_motor_get_target_position(VALUE self) {
195
+ return ph_get_double(get_ph_handle(self), (phidget_get_double_func)PhidgetMotorPositionController_getTargetPosition);
196
+ }
197
+
198
+ VALUE ph_motor_set_target_position(VALUE self, VALUE target_position) {
199
+ ph_raise(PhidgetMotorPositionController_setTargetPosition((PhidgetMotorPositionControllerHandle)get_ph_handle(self), NUM2DBL(target_position)));
200
+ return Qnil;
201
+ }
202
+
203
+ VALUE ph_motor_get_velocity_limit(VALUE self) {
204
+ return ph_get_double(get_ph_handle(self), (phidget_get_double_func)PhidgetMotorPositionController_getVelocityLimit);
205
+ }
206
+
207
+ VALUE ph_motor_set_velocity_limit(VALUE self, VALUE velocity) {
208
+ ph_raise(PhidgetMotorPositionController_setVelocityLimit((PhidgetMotorPositionControllerHandle)get_ph_handle(self), NUM2DBL(velocity)));
209
+ return Qnil;
210
+ }
211
+
212
+ VALUE ph_motor_get_min_velocity_limit(VALUE self) {
213
+ return ph_get_double(get_ph_handle(self), (phidget_get_double_func)PhidgetMotorPositionController_getMinVelocityLimit);
214
+ }
215
+
216
+ VALUE ph_motor_get_max_velocity_limit(VALUE self) {
217
+ return ph_get_double(get_ph_handle(self), (phidget_get_double_func)PhidgetMotorPositionController_getMaxVelocityLimit);
218
+ }
219
+
220
+
221
+ void CCONV ph_motor_on_duty_cycle_update(PhidgetMotorPositionControllerHandle phid, void *userPtr, double duty_cycle) {
222
+ ph_callback_data_t *callback_data = ((ph_callback_data_t *)userPtr);
223
+ while(sem_wait(&callback_data->handler_ready)!=0) {};
224
+ callback_data->arg1 = DBL2NUM(duty_cycle);
225
+ callback_data->arg2 = Qnil;
226
+ callback_data->arg3 = Qnil;
227
+ callback_data->arg4 = Qnil;
228
+ sem_post(&callback_data->callback_called);
229
+ }
230
+
231
+
232
+ VALUE ph_motor_set_on_duty_cycle_update_handler(VALUE self, VALUE handler) {
233
+ ph_data_t *ph = get_ph_data(self);
234
+ ph_callback_data_t *callback_data = &ph->dev_callbacks[MOTOR_DUTY_CYCLE_UPDATE_CALLBACK];
235
+ if( TYPE(handler) == T_NIL ) {
236
+ callback_data->callback = T_NIL;
237
+ callback_data->exit = true;
238
+ ph_raise(PhidgetMotorPositionController_setOnDutyCycleUpdateHandler((PhidgetMotorPositionControllerHandle)ph->handle, NULL, (void *)NULL));
239
+ sem_post(&callback_data->callback_called);
240
+ } else {
241
+ callback_data->exit = false;
242
+ callback_data->phidget = self;
243
+ callback_data->callback = handler;
244
+ ph_raise(PhidgetMotorPositionController_setOnDutyCycleUpdateHandler((PhidgetMotorPositionControllerHandle)ph->handle, ph_motor_on_duty_cycle_update, (void *)callback_data));
245
+ ph_callback_thread(callback_data);
246
+ }
247
+ return Qnil;
248
+ }
249
+
250
+
251
+ void CCONV ph_motor_on_position_change(PhidgetMotorPositionControllerHandle phid, void *userPtr, double position) {
252
+ ph_callback_data_t *callback_data = ((ph_callback_data_t *)userPtr);
253
+ while(sem_wait(&callback_data->handler_ready)!=0) {};
254
+ callback_data->arg1 = DBL2NUM(position);
255
+ callback_data->arg2 = Qnil;
256
+ callback_data->arg3 = Qnil;
257
+ callback_data->arg4 = Qnil;
258
+ sem_post(&callback_data->callback_called);
259
+ }
260
+
261
+
262
+ VALUE ph_motor_set_on_position_change_handler(VALUE self, VALUE handler) {
263
+ ph_data_t *ph = get_ph_data(self);
264
+ ph_callback_data_t *callback_data = &ph->dev_callbacks[MOTOR_POSITION_UPDATE_CALLBACK];
265
+ if( TYPE(handler) == T_NIL ) {
266
+ callback_data->callback = T_NIL;
267
+ callback_data->exit = true;
268
+ ph_raise(PhidgetMotorPositionController_setOnPositionChangeHandler((PhidgetMotorPositionControllerHandle)ph->handle, NULL, (void *)NULL));
269
+ sem_post(&callback_data->callback_called);
270
+ } else {
271
+ callback_data->exit = false;
272
+ callback_data->phidget = self;
273
+ callback_data->callback = handler;
274
+ ph_raise(PhidgetMotorPositionController_setOnPositionChangeHandler((PhidgetMotorPositionControllerHandle)ph->handle, ph_motor_on_position_change, (void *)callback_data));
275
+ ph_callback_thread(callback_data);
276
+ }
277
+ return Qnil;
278
+ }
279
+
280
+
281
+ void CCONV ph_motor_target_position_async(PhidgetHandle phid, void *userPtr, PhidgetReturnCode res) {
282
+ ph_callback_data_t *callback_data = ((ph_callback_data_t *)userPtr);
283
+ callback_data->exit = true;
284
+ callback_data->arg1 = INT2NUM(res);
285
+ callback_data->arg2 = Qnil;
286
+ callback_data->arg3 = Qnil;
287
+ callback_data->arg4 = Qnil;
288
+ sem_post(&callback_data->callback_called);
289
+ }
290
+
291
+
292
+ VALUE ph_motor_set_target_position_async(VALUE self, VALUE position, VALUE handler) {
293
+ ph_data_t *ph = get_ph_data(self);
294
+ ph_callback_data_t *callback_data = &ph->dev_callbacks[MOTOR_TARGET_POSITION_ASYNC_CALLBACK];
295
+ if( TYPE(handler) == T_NIL ) {
296
+ PhidgetMotorPositionController_setTargetPosition_async((PhidgetMotorPositionControllerHandle)ph->handle, NUM2DBL(position), NULL, (void *)NULL);
297
+ } else {
298
+ callback_data->exit = false;
299
+ callback_data->phidget = self;
300
+ callback_data->callback = handler;
301
+ PhidgetMotorPositionController_setTargetPosition_async((PhidgetMotorPositionControllerHandle)ph->handle, NUM2DBL(position), ph_motor_target_position_async, (void *)callback_data);
302
+ ph_callback_thread(callback_data);
303
+ }
304
+ return Qnil;
305
+ }
306
+
307
+
308
+ void Init_motor_position_controller() {
309
+ VALUE ph_module = rb_const_get(rb_cObject, rb_intern("Phidgets"));
310
+ VALUE ph_common = rb_const_get(ph_module, rb_intern("Common"));
311
+ VALUE ph_motor = rb_define_class_under(ph_module, "MotorPositionController", ph_common);
312
+
313
+ /* Document-method: new
314
+ * call-seq: new
315
+ *
316
+ * Creates a Phidget MotorPositionController object.
317
+ */
318
+ rb_define_method(ph_motor, "initialize", ph_motor_init, 0);
319
+
320
+ /* Document-method: getAcceleration
321
+ * call-seq: getAcceleration -> acceleration
322
+ *
323
+ * The rate at which the controller can change the motor's velocity.
324
+ * Units for Position, VelocityLimit, Acceleration, and DeadBand can be set by the user through the RescaleFactor.
325
+ * The RescaleFactor allows you to use more intuitive units such as rotations, or degrees.
326
+ */
327
+ rb_define_method(ph_motor, "getAcceleration", ph_motor_get_acceleration, 0);
328
+ rb_define_alias(ph_motor, "acceleration", "getAcceleration");
329
+
330
+ /* Document-method: setAcceleration
331
+ * call-seq: setAcceleration(acceleration)
332
+ *
333
+ * The rate at which the controller can change the motor's velocity.
334
+ * Units for Position, VelocityLimit, Acceleration, and DeadBand can be set by the user through the RescaleFactor.
335
+ * The RescaleFactor allows you to use more intuitive units such as rotations, or degrees.
336
+ */
337
+ rb_define_method(ph_motor, "setAcceleration", ph_motor_set_acceleration, 1);
338
+ rb_define_alias(ph_motor, "acceleration=", "setAcceleration");
339
+
340
+ /* Document-method: getMinAcceleration
341
+ * call-seq: getMinAcceleration -> min_acceleration
342
+ *
343
+ * The minimum value that Acceleration can be set to.
344
+ * Units for Position, VelocityLimit, Acceleration, and DeadBand can be set by the user through the RescaleFactor.
345
+ * The RescaleFactor allows you to use more intuitive units such as rotations, or degrees.
346
+ */
347
+ rb_define_method(ph_motor, "getMinAcceleration", ph_motor_get_min_acceleration, 0);
348
+ rb_define_alias(ph_motor, "min_acceleration", "getMinAcceleration");
349
+
350
+ /* Document-method: getMaxAcceleration
351
+ * call-seq: getMaxAcceleration -> max_acceleration
352
+ *
353
+ * The maximum value that Acceleration can be set to.
354
+ * Units for Position, VelocityLimit, Acceleration, and DeadBand can be set by the user through the RescaleFactor.
355
+ * The RescaleFactor allows you to use more intuitive units such as rotations, or degrees.
356
+ */
357
+ rb_define_method(ph_motor, "getMaxAcceleration", ph_motor_get_max_acceleration, 0);
358
+ rb_define_alias(ph_motor, "max_acceleration", "getMaxAcceleration");
359
+
360
+ /* Document-method: getCurrentLimit
361
+ * call-seq: getCurrentLimit -> current_limit
362
+ *
363
+ * The controller will limit the current through the motor to this value.
364
+ */
365
+ rb_define_method(ph_motor, "getCurrentLimit", ph_motor_get_current_limit, 0);
366
+ rb_define_alias(ph_motor, "current_limit", "getCurrentLimit");
367
+
368
+ /* Document-method: setCurrentLimit
369
+ * call-seq: setCurrentLimit(current_limit)
370
+ *
371
+ * The controller will limit the current through the motor to this value.
372
+ */
373
+ rb_define_method(ph_motor, "setCurrentLimit", ph_motor_set_current_limit, 1);
374
+ rb_define_alias(ph_motor, "current_limit=", "setCurrentLimit");
375
+
376
+ /* Document-method: getMinCurrentLimit
377
+ * call-seq: getMinCurrentLimit -> current_limit
378
+ *
379
+ * The minimum current limit that can be set for the device.
380
+ */
381
+ rb_define_method(ph_motor, "getMinCurrentLimit", ph_motor_get_min_current_limit, 0);
382
+ rb_define_alias(ph_motor, "min_current_limit", "getMinCurrentLimit");
383
+
384
+ /* Document-method: getMaxCurrentLimit
385
+ * call-seq: getMaxCurrentLimit -> current_limit
386
+ *
387
+ * The maximum current limit that can be set for the device.
388
+ */
389
+ rb_define_method(ph_motor, "getMaxCurrentLimit", ph_motor_get_max_current_limit, 0);
390
+ rb_define_alias(ph_motor, "max_current_limit", "getMaxCurrentLimit");
391
+
392
+ /* Document-method: getCurrentRegulatorGain
393
+ * call-seq: getCurrentRegulatorGain -> regulator_gain
394
+ *
395
+ * Depending on power supply voltage and motor coil inductance, current through the motor can change relatively slowly or extremely rapidly.
396
+ * A physically larger DC Motor will typically have a lower inductance, requiring a higher current regulator gain.
397
+ * A higher power supply voltage will result in motor current changing more rapidly, requiring a higher current regulator gain.
398
+ * If the current regulator gain is too small, spikes in current will occur, causing large variations in torque, and possibly damaging the motor controller.
399
+ * If the current regulator gain is too high, the current will jitter, causing the motor to sound 'rough', especially when changing directions.
400
+ */
401
+ rb_define_method(ph_motor, "getCurrentRegulatorGain", ph_motor_get_current_regulator_gain, 0);
402
+ rb_define_alias(ph_motor, "current_regulator_gain", "getCurrentRegulatorGain");
403
+
404
+ /* Document-method: setCurrentRegulatorGain
405
+ * call-seq: setCurrentRegulatorGain(regulator_gain)
406
+ *
407
+ * Depending on power supply voltage and motor coil inductance, current through the motor can change relatively slowly or extremely rapidly.
408
+ * A physically larger DC Motor will typically have a lower inductance, requiring a higher current regulator gain.
409
+ * A higher power supply voltage will result in motor current changing more rapidly, requiring a higher current regulator gain.
410
+ * If the current regulator gain is too small, spikes in current will occur, causing large variations in torque, and possibly damaging the motor controller.
411
+ * If the current regulator gain is too high, the current will jitter, causing the motor to sound 'rough', especially when changing directions.
412
+ */
413
+ rb_define_method(ph_motor, "setCurrentRegulatorGain", ph_motor_set_current_regulator_gain, 1);
414
+ rb_define_alias(ph_motor, "current_regulator_gain=", "setCurrentRegulatorGain");
415
+
416
+ /* Document-method: getMinCurrentRegulatorGain
417
+ * call-seq: getMinCurrentRegulatorGain -> regulator_gain
418
+ *
419
+ * The minimum current regulator gain for the device.
420
+ */
421
+ rb_define_method(ph_motor, "getMinCurrentRegulatorGain", ph_motor_get_min_current_regulator_gain, 0);
422
+ rb_define_alias(ph_motor, "min_current_regulator_gain", "getMinCurrentRegulatorGain");
423
+
424
+ /* Document-method: getMaxCurrentRegulatorGain
425
+ * call-seq: getMaxCurrentRegulatorGain -> regulator_gain
426
+ *
427
+ * The maximum current regulator gain for the device.
428
+ */
429
+ rb_define_method(ph_motor, "getMaxCurrentRegulatorGain", ph_motor_get_max_current_regulator_gain, 0);
430
+ rb_define_alias(ph_motor, "max_current_regulator_gain", "getMaxCurrentRegulatorGain");
431
+
432
+ /* Document-method: getDataInterval
433
+ * call-seq: getDataInterval -> interval
434
+ *
435
+ * The DataInterval is the time that must elapse before the controller will fire another CurrentChange event.
436
+ * The data interval is bounded by MinDataInterval and MaxDataInterval.
437
+ * The timing between CurrentChange events can also affected by the CurrentChangeTrigger.
438
+ */
439
+ rb_define_method(ph_motor, "getDataInterval", ph_motor_get_data_interval, 0);
440
+ rb_define_alias(ph_motor, "data_interval", "getDataInterval");
441
+
442
+ /* Document-method: setDataInterval
443
+ * call-seq: setDataInterval(interval)
444
+ *
445
+ * The DataInterval is the time that must elapse before the controller will fire another CurrentChange event.
446
+ * The data interval is bounded by MinDataInterval and MaxDataInterval.
447
+ * The timing between CurrentChange events can also affected by the CurrentChangeTrigger.
448
+ */
449
+ rb_define_method(ph_motor, "setDataInterval", ph_motor_set_data_interval, 1);
450
+ rb_define_alias(ph_motor, "data_interval=", "setDataInterval");
451
+
452
+ /* Document-method: getMinDataInterval
453
+ * call-seq: getMinDataInterval -> interval
454
+ *
455
+ * The minimum value that DataInterval can be set to.
456
+ */
457
+ rb_define_method(ph_motor, "getMinDataInterval", ph_motor_get_min_data_interval, 0);
458
+ rb_define_alias(ph_motor, "min_data_interval", "getMinDataInterval");
459
+
460
+ /* Document-method: getMaxDataInterval
461
+ * call-seq: getMaxDataInterval -> interval
462
+ *
463
+ * The maximum value that DataInterval can be set to.
464
+ */
465
+ rb_define_method(ph_motor, "getMaxDataInterval", ph_motor_get_max_data_interval, 0);
466
+ rb_define_alias(ph_motor, "max_data_interval", "getMaxDataInterval");
467
+
468
+ /* Document-method: getDeadBand
469
+ * call-seq: getDeadBand -> dead_band
470
+ *
471
+ * Depending on your system, it may not be possible to bring the position error (TargetPosition - Position) to zero.
472
+ * A small error can lead to the motor continually 'hunting' for a target position, which can cause unwanted effects.
473
+ * By setting a non-zero DeadBand, the position controller will relax control of the motor within the deadband, preventing the 'hunting' behavior.
474
+ * Units for Position, VelocityLimit, Acceleration, and DeadBand can be set by the user through the RescaleFactor.
475
+ * The RescaleFactor allows you to use more intuitive units such as rotations, or degrees.
476
+ */
477
+ rb_define_method(ph_motor, "getDeadBand", ph_motor_get_dead_band, 0);
478
+ rb_define_alias(ph_motor, "dead_band", "getDeadBand");
479
+
480
+ /* Document-method: setDeadBand
481
+ * call-seq: setDeadBand(dead_band)
482
+ *
483
+ * Depending on your system, it may not be possible to bring the position error (TargetPosition - Position) to zero.
484
+ * A small error can lead to the motor continually 'hunting' for a target position, which can cause unwanted effects.
485
+ * By setting a non-zero DeadBand, the position controller will relax control of the motor within the deadband, preventing the 'hunting' behavior.
486
+ * Units for Position, VelocityLimit, Acceleration, and DeadBand can be set by the user through the RescaleFactor.
487
+ * The RescaleFactor allows you to use more intuitive units such as rotations, or degrees.
488
+ */
489
+ rb_define_method(ph_motor, "setDeadBand", ph_motor_set_dead_band, 1);
490
+ rb_define_alias(ph_motor, "dead_band=", "setDeadBand");
491
+
492
+ /* Document-method: getDutyCycle
493
+ * call-seq: getDutyCycle -> duty_cycle
494
+ *
495
+ * The most recent duty cycle value that the controller has reported.
496
+ * This value will be between -1 and 1 where a sign change (±) is indicitave of a direction change.
497
+ * Note that DutyCycle is merely an indication of the average voltage across the motor. At a constant load, an increase in DutyCycle indicates an increase in motor speed.
498
+ * The units of DutyCycle refer to 'duty cycle'. This is because the controller must rapidly switch the power on/off (i.e. change the duty cycle) in order to manipulate the voltage across the motor.
499
+ */
500
+ rb_define_method(ph_motor, "getDutyCycle", ph_motor_get_duty_cycle, 0);
501
+ rb_define_alias(ph_motor, "duty_cycle", "getDutyCycle");
502
+
503
+ /* Document-method: getEngaged
504
+ * call-seq: getEngaged -> engaged
505
+ *
506
+ * When engaged, a motor has the ability to be positioned. When disengaged, no commands are sent to the motor.
507
+ * This function is useful for completely relaxing a motor once it has reached the target position.
508
+ */
509
+ rb_define_method(ph_motor, "getEngaged", ph_motor_get_engaged, 0);
510
+ rb_define_alias(ph_motor, "engaged?", "getEngaged");
511
+
512
+ /* Document-method: setEngaged
513
+ * call-seq: setEngaged(engaged)
514
+ *
515
+ * When engaged, a motor has the ability to be positioned. When disengaged, no commands are sent to the motor.
516
+ * This function is useful for completely relaxing a motor once it has reached the target position.
517
+ */
518
+ rb_define_method(ph_motor, "setEngaged", ph_motor_set_engaged, 1);
519
+ rb_define_alias(ph_motor, "engaged=", "setEngaged");
520
+
521
+ /* Document-method: getFanMode
522
+ * call-seq: getFanMode -> fan_mode
523
+ *
524
+ * The FanMode dictates the operating condition of the fan.
525
+ * Choose between on, off, or automatic (based on temperature).
526
+ * If the FanMode is set to automatic, the fan will turn on when the temperature reaches 70°C and it will remain on until the temperature falls below 55°C.
527
+ * If the FanMode is off, the controller will still turn on the fan if the temperature reaches 85°C and it will remain on until it falls below 70°C.
528
+ */
529
+ rb_define_method(ph_motor, "getFanMode", ph_motor_get_fan_mode, 0);
530
+ rb_define_alias(ph_motor, "fan_mode", "getFanMode");
531
+
532
+ /* Document-method: setFanMode
533
+ * call-seq: setFanMode(fan_mode)
534
+ *
535
+ * The FanMode dictates the operating condition of the fan.
536
+ * Choose between on, off, or automatic (based on temperature).
537
+ * If the FanMode is set to automatic, the fan will turn on when the temperature reaches 70°C and it will remain on until the temperature falls below 55°C.
538
+ * If the FanMode is off, the controller will still turn on the fan if the temperature reaches 85°C and it will remain on until it falls below 70°C.
539
+ */
540
+ rb_define_method(ph_motor, "setFanMode", ph_motor_set_fan_mode, 1);
541
+ rb_define_alias(ph_motor, "fan_mode=", "setFanMode");
542
+
543
+ /* Document-method: getIOMode
544
+ * call-seq: getIOMode -> io_mode
545
+ *
546
+ * The encoder interface mode. Match the mode to the type of encoder you have attached.
547
+ * It is recommended to only change this when the encoder is disabled in order to avoid unexpected results.
548
+ */
549
+ rb_define_method(ph_motor, "getIOMode", ph_motor_get_io_mode, 0);
550
+ rb_define_alias(ph_motor, "io_mode", "getIOMode");
551
+
552
+ /* Document-method: setIOMode
553
+ * call-seq: setIOMode(io_mode)
554
+ *
555
+ * The encoder interface mode. Match the mode to the type of encoder you have attached.
556
+ * It is recommended to only change this when the encoder is disabled in order to avoid unexpected results.
557
+ */
558
+ rb_define_method(ph_motor, "setIOMode", ph_motor_set_io_mode, 1);
559
+ rb_define_alias(ph_motor, "io_mode=", "setIOMode");
560
+
561
+ /* Document-method: getKd
562
+ * call-seq: getKd -> kd
563
+ *
564
+ * Derivative gain constant. A higher Kd will help reduce oscillations.
565
+ */
566
+ rb_define_method(ph_motor, "getKd", ph_motor_get_kd, 0);
567
+ rb_define_alias(ph_motor, "kd", "getKd");
568
+
569
+ /* Document-method: setKd
570
+ * call-seq: setKd(kd)
571
+ *
572
+ * Derivative gain constant. A higher Kd will help reduce oscillations.
573
+ */
574
+ rb_define_method(ph_motor, "setKd", ph_motor_set_kd, 1);
575
+ rb_define_alias(ph_motor, "kd=", "setKd");
576
+
577
+ /* Document-method: getKi
578
+ * call-seq: getKi -> ki
579
+ *
580
+ * Integral gain constant. The integral term will help eliminate steady-state error.
581
+ */
582
+ rb_define_method(ph_motor, "getKi", ph_motor_get_ki, 0);
583
+ rb_define_alias(ph_motor, "ki", "getKi");
584
+
585
+ /* Document-method: setKi
586
+ * call-seq: setKi(ki)
587
+ *
588
+ * Integral gain constant. The integral term will help eliminate steady-state error.
589
+ */
590
+ rb_define_method(ph_motor, "setKi", ph_motor_set_ki, 1);
591
+ rb_define_alias(ph_motor, "ki=", "setKi");
592
+
593
+ /* Document-method: getKp
594
+ * call-seq: getKp -> kp
595
+ *
596
+ * Proportional gain constant. A small Kp value will result in a less responsive controller, however, if Kp is too high, the system can become unstable.
597
+ */
598
+ rb_define_method(ph_motor, "getKp", ph_motor_get_kp, 0);
599
+ rb_define_alias(ph_motor, "kp", "getKp");
600
+
601
+ /* Document-method: setKp
602
+ * call-seq: setKp(kp)
603
+ *
604
+ * Proportional gain constant. A small Kp value will result in a less responsive controller, however, if Kp is too high, the system can become unstable.
605
+ */
606
+ rb_define_method(ph_motor, "setKp", ph_motor_set_kp, 1);
607
+ rb_define_alias(ph_motor, "kp=", "setKp");
608
+
609
+ /* Document-method: getPosition
610
+ * call-seq: getPosition -> position
611
+ *
612
+ * The most recent position value that the controller has reported.
613
+ * This value will always be between MinPosition and MaxPosition.
614
+ * Units for Position, VelocityLimit, Acceleration, and DeadBand can be set by the user through the RescaleFactor.
615
+ * The RescaleFactor allows you to use more intuitive units such as rotations, or degrees.
616
+ */
617
+ rb_define_method(ph_motor, "getPosition", ph_motor_get_position, 0);
618
+ rb_define_alias(ph_motor, "position", "getPosition");
619
+
620
+ /* Document-method: getMinPosition
621
+ * call-seq: getMinPosition -> min_position
622
+ *
623
+ * The minimum value that TargetPosition can be set to.
624
+ */
625
+ rb_define_method(ph_motor, "getMinPosition", ph_motor_get_min_position, 0);
626
+ rb_define_alias(ph_motor, "min_position", "getMinPosition");
627
+
628
+ /* Document-method: getMaxPosition
629
+ * call-seq: getMaxPosition -> max_position
630
+ *
631
+ * The maximum value that TargetPosition can be set to.
632
+ */
633
+ rb_define_method(ph_motor, "getMaxPosition", ph_motor_get_max_position, 0);
634
+ rb_define_alias(ph_motor, "max_position", "getMaxPosition");
635
+
636
+ /* Document-method: addPositionOffset
637
+ * call-seq: addPositionOffset(offset)
638
+ *
639
+ * Adds an offset (positive or negative) to the current position. Useful for zeroing position.
640
+ */
641
+ rb_define_method(ph_motor, "addPositionOffset", ph_motor_add_position_offset, 1);
642
+ rb_define_alias(ph_motor, "add_position_offset", "addPositionOffset");
643
+
644
+ /* Document-method: getRescaleFactor
645
+ * call-seq: getRescaleFactor -> rescale_factor
646
+ *
647
+ * Change the units of your parameters so that your application is more intuitive.
648
+ * Units for Position, VelocityLimit, Acceleration, and DeadBand can be set by the user through the RescaleFactor.
649
+ * The RescaleFactor allows you to use more intuitive units such as rotations, or degrees.
650
+ */
651
+ rb_define_method(ph_motor, "getRescaleFactor", ph_motor_get_rescale_factor, 0);
652
+ rb_define_alias(ph_motor, "rescale_factor", "getRescaleFactor");
653
+
654
+ /* Document-method: setRescaleFactor
655
+ * call-seq: setRescaleFactor(rescale_factor)
656
+ *
657
+ * Change the units of your parameters so that your application is more intuitive.
658
+ * Units for Position, VelocityLimit, Acceleration, and DeadBand can be set by the user through the RescaleFactor.
659
+ * The RescaleFactor allows you to use more intuitive units such as rotations, or degrees.
660
+ */
661
+ rb_define_method(ph_motor, "setRescaleFactor", ph_motor_set_rescale_factor, 1);
662
+ rb_define_alias(ph_motor, "rescale_factor=", "setRescaleFactor");
663
+
664
+ /* Document-method: getStallVelocity
665
+ * call-seq: getStallVelocity -> stall_velocity
666
+ *
667
+ * Before reading this description, it is important to note the difference between the units of StallVelocity and Velocity.
668
+ * Velocity is a number between -1 and 1 with units of 'duty cycle'. It simply represents the average voltage across the motor.
669
+ * StallVelocity represents a real velocity (e.g. m/s, RPM, etc.) and the units are determined by the RescaleFactor.
670
+ * With a RescaleFactor of 1, the default units would be in commutations per second.
671
+ * If the load on your motor is large, your motor may begin rotating more slowly, or even fully stall.
672
+ * Depending on the voltage across your motor, this may result in a large amount of current through both the controller and the motor.
673
+ * In order to prevent damage in these situations, you can use the StallVelocity property.
674
+ *
675
+ * The StallVelocity should be set to the lowest velocity you would expect from your motor.
676
+ * The controller will then monitor the motor's velocity, as well as the Velocity, and prevent a 'dangerous stall' from occuring.
677
+ * If the controller detects a dangerous stall, it will immediately disengage the motor (i.e. Engaged will be set to false) and an error will be reported to your program.
678
+ * A 'dangerous stall' will occur faster when the Velocity is higher (i.e. when the average voltage across the motor is higher)
679
+ * A 'dangerous stall' will occur faster as (StallVelocity - motor velocity) becomes larger .
680
+ * Setting StallVelocity to 0 will turn off stall protection functionality.
681
+ */
682
+ rb_define_method(ph_motor, "getStallVelocity", ph_motor_get_stall_velocity, 0);
683
+ rb_define_alias(ph_motor, "stall_velocity", "getStallVelocity");
684
+
685
+ /* Document-method: setStallVelocity
686
+ * call-seq: setStallVelocity(stall_velocity)
687
+ *
688
+ * Before reading this description, it is important to note the difference between the units of StallVelocity and Velocity.
689
+ * Velocity is a number between -1 and 1 with units of 'duty cycle'. It simply represents the average voltage across the motor.
690
+ * StallVelocity represents a real velocity (e.g. m/s, RPM, etc.) and the units are determined by the RescaleFactor.
691
+ * With a RescaleFactor of 1, the default units would be in commutations per second.
692
+ * If the load on your motor is large, your motor may begin rotating more slowly, or even fully stall.
693
+ * Depending on the voltage across your motor, this may result in a large amount of current through both the controller and the motor.
694
+ * In order to prevent damage in these situations, you can use the StallVelocity property.
695
+ *
696
+ * The StallVelocity should be set to the lowest velocity you would expect from your motor.
697
+ * The controller will then monitor the motor's velocity, as well as the Velocity, and prevent a 'dangerous stall' from occuring.
698
+ * If the controller detects a dangerous stall, it will immediately disengage the motor (i.e. Engaged will be set to false) and an error will be reported to your program.
699
+ * A 'dangerous stall' will occur faster when the Velocity is higher (i.e. when the average voltage across the motor is higher)
700
+ * A 'dangerous stall' will occur faster as (StallVelocity - motor velocity) becomes larger .
701
+ * Setting StallVelocity to 0 will turn off stall protection functionality.
702
+ */
703
+ rb_define_method(ph_motor, "setStallVelocity", ph_motor_set_stall_velocity, 1);
704
+ rb_define_alias(ph_motor, "stall_velocity=", "setStallVelocity");
705
+
706
+ /* Document-method: getMinStallVelocity
707
+ * call-seq: getMinStallVelocity -> stall_velocity
708
+ *
709
+ * The lower bound of StallVelocity.
710
+ */
711
+ rb_define_method(ph_motor, "getMinStallVelocity", ph_motor_get_min_stall_velocity, 0);
712
+ rb_define_alias(ph_motor, "min_stall_velocity", "getMinStallVelocity");
713
+
714
+ /* Document-method: getMaxStallVelocity
715
+ * call-seq: getMaxStallVelocity -> stall_velocity
716
+ *
717
+ * The upper bound of StallVelocity.
718
+ */
719
+ rb_define_method(ph_motor, "getMaxStallVelocity", ph_motor_get_max_stall_velocity, 0);
720
+ rb_define_alias(ph_motor, "max_stall_velocity", "getMaxStallVelocity");
721
+
722
+ /* Document-method: getTargetPosition
723
+ * call-seq: getTargetPosition -> target_position
724
+ *
725
+ * If the controller is configured and the TargetPosition is set, the motor will try to reach the TargetPosition.
726
+ * If the DeadBand is non-zero, the final position of the motor may not match the TargetPosition
727
+ * Units for Position, VelocityLimit, Acceleration, and DeadBand can be set by the user through the RescaleFactor.
728
+ * The RescaleFactor allows you to use more intuitive units such as rotations, or degrees.
729
+ */
730
+ rb_define_method(ph_motor, "getTargetPosition", ph_motor_get_target_position, 0);
731
+ rb_define_alias(ph_motor, "target_position", "getTargetPosition");
732
+
733
+ /* Document-method: setTargetPosition
734
+ * call-seq: setTargetPosition(target_position)
735
+ *
736
+ * If the controller is configured and the TargetPosition is set, the motor will try to reach the TargetPosition.
737
+ * If the DeadBand is non-zero, the final position of the motor may not match the TargetPosition
738
+ * Units for Position, VelocityLimit, Acceleration, and DeadBand can be set by the user through the RescaleFactor.
739
+ * The RescaleFactor allows you to use more intuitive units such as rotations, or degrees.
740
+ */
741
+ rb_define_method(ph_motor, "setTargetPosition", ph_motor_set_target_position, 1);
742
+ rb_define_alias(ph_motor, "target_position=", "setTargetPosition");
743
+
744
+ /* Document-method: getVelocityLimit
745
+ * call-seq: getVelocityLimit -> velocity_limit
746
+ *
747
+ * When moving, the motor velocity will be limited by this value.
748
+ * VelocityLimit is bounded by MinVelocityLimit and MaxVelocityLimit.
749
+ * Units for Position, VelocityLimit, Acceleration, and DeadBand can be set by the user through the RescaleFactor.
750
+ * The RescaleFactor allows you to use more intuitive units such as rotations, or degrees.
751
+ */
752
+ rb_define_method(ph_motor, "getVelocityLimit", ph_motor_get_velocity_limit, 0);
753
+ rb_define_alias(ph_motor, "velocity_limit", "getVelocityLimit");
754
+
755
+ /* Document-method: setVelocityLimit
756
+ * call-seq: setVelocityLimit(velocity_limit)
757
+ *
758
+ * When moving, the motor velocity will be limited by this value.
759
+ * VelocityLimit is bounded by MinVelocityLimit and MaxVelocityLimit.
760
+ * Units for Position, VelocityLimit, Acceleration, and DeadBand can be set by the user through the RescaleFactor.
761
+ * The RescaleFactor allows you to use more intuitive units such as rotations, or degrees.
762
+ */
763
+ rb_define_method(ph_motor, "setVelocityLimit", ph_motor_set_velocity_limit, 1);
764
+ rb_define_alias(ph_motor, "velocity_limit=", "setVelocityLimit");
765
+
766
+ /* Document-method: getMinVelocityLimit
767
+ * call-seq: getMinVelocityLimit -> velocity_limit
768
+ *
769
+ * The minimum value that VelocityLimit can be set to.
770
+ */
771
+ rb_define_method(ph_motor, "getMinVelocityLimit", ph_motor_get_min_velocity_limit, 0);
772
+ rb_define_alias(ph_motor, "min_velocity_limit", "getMinVelocityLimit");
773
+
774
+ /* Document-method: getMaxVelocityLimit
775
+ * call-seq: getMaxVelocityLimit -> velocity_limit
776
+ *
777
+ * The maximum value that VelocityLimit can be set to.
778
+ */
779
+ rb_define_method(ph_motor, "getMaxVelocityLimit", ph_motor_get_max_velocity_limit, 0);
780
+ rb_define_alias(ph_motor, "max_velocity_limit", "getMaxVelocityLimit");
781
+
782
+
783
+ rb_define_private_method(ph_motor, "ext_setOnDutyCycleUpdateHandler", ph_motor_set_on_duty_cycle_update_handler, 1);
784
+ rb_define_private_method(ph_motor, "ext_setOnPositionChangeHandler", ph_motor_set_on_position_change_handler, 1);
785
+ rb_define_private_method(ph_motor, "ext_setTargetPosition_async", ph_motor_set_target_position_async, 2);
786
+ }
787
+