UNPKG

23.9 kBJavaScriptView Raw
1var Board = require("./board");
2var Expander = require("./expander.js");
3var EVS = require("./evshield");
4var __ = require("./fn");
5var events = require("events");
6var util = require("util");
7var Collection = require("./mixins/collection");
8var Sensor = require("./sensor");
9var ShiftRegister = require("./shiftregister");
10
11var priv = new Map();
12var registers = new Map();
13
14function registerKey(registerOpts) {
15 return ["clock", "data", "latch"].reduce(function(accum, key) {
16 return accum + "." + registerOpts[key];
17 }, "");
18}
19
20function latch(state, bit, on) {
21 return on ? state |= (1 << bit) : state &= ~(1 << bit);
22}
23
24function updateShiftRegister(motor, dir) {
25 var rKey = registerKey(motor.opts.register),
26 register = registers.get(motor.board)[rKey],
27 latchState = register.value,
28 bits = priv.get(motor).bits,
29 forward = dir !== "reverse";
30
31 // There are two ShiftRegister bits which we need to change based on the
32 // direction of the motor. These will be the pins that control the HBridge
33 // on the board. They will get flipped high/low based on the current flow
34 // in the HBridge.
35 latchState = latch(latchState, bits.a, forward);
36 latchState = latch(latchState, bits.b, !forward);
37
38 if (register.value !== latchState) {
39 register.send(latchState);
40 }
41}
42
43var Controllers = {
44 ShiftRegister: {
45 initialize: {
46 value: function(opts) {
47 var rKey = registerKey(opts.register);
48
49 if (!opts.bits || opts.bits.a === undefined || opts.bits.b === undefined) {
50 throw new Error("ShiftRegister Motors MUST contain HBRIDGE bits {a, b}");
51 }
52
53 priv.get(this).bits = opts.bits;
54
55 if (!registers.has(this.board)) {
56 registers.set(this.board, {});
57 }
58
59 if (!registers.get(this.board)[rKey]) {
60 registers.get(this.board)[rKey] = new ShiftRegister({
61 board: this.board,
62 pins: opts.register
63 });
64 }
65
66 this.io.pinMode(this.pins.pwm, this.io.MODES.PWM);
67 }
68 },
69 dir: {
70 value: function(dir) {
71 this.stop();
72
73 updateShiftRegister(this, dir.name);
74
75 this.direction = dir;
76
77 process.nextTick(this.emit.bind(this, dir.name));
78
79 return this;
80 }
81 }
82 },
83 PCA9685: {
84 setPWM: {
85 writable: true,
86 value: function(pin, speed) {
87 var state = priv.get(this);
88 state.expander.analogWrite(pin, speed);
89 }
90 },
91 setPin: {
92 writable: true,
93 value: function(pin, value) {
94 var state = priv.get(this);
95 state.expander.digitalWrite(pin, value);
96 }
97 },
98 initialize: {
99 value: function(opts) {
100
101 var state = priv.get(this);
102
103 this.address = opts.address || 0x40;
104 this.pwmRange = opts.pwmRange || [0, 4080];
105 this.frequency = opts.frequency || 50;
106
107 state.expander = Expander.get({
108 address: this.address,
109 controller: this.controller,
110 bus: this.bus,
111 pwmRange: this.pwmRange,
112 frequency: this.frequency,
113 });
114
115 Object.keys(this.pins).forEach(function(pinName) {
116 this.pins[pinName] = state.expander.normalize(this.pins[pinName]);
117 }, this);
118
119 }
120 }
121 },
122 EVS_EV3: {
123 initialize: {
124 value: function(opts) {
125 var state = priv.get(this);
126
127 state.shield = EVS.shieldPort(opts.pin);
128 state.ev3 = new EVS(Object.assign(opts, {
129 io: this.io
130 }));
131
132 this.opts.pins = {
133 pwm: opts.pin,
134 dir: opts.pin,
135 };
136 }
137 },
138 setPWM: {
139 value: function(pin, value) {
140 var state = priv.get(this);
141
142 var register = state.shield.motor === EVS.M1 ? EVS.SPEED_M1 : EVS.SPEED_M2;
143 var speed = __.scale(value, 0, 255, 0, 100) | 0;
144
145 if (value === 0) {
146 state.ev3.write(state.shield, EVS.COMMAND, EVS.Motor_Reset);
147 } else {
148 if (!this.direction.value) {
149 speed = -speed;
150 }
151
152 var data = [
153 // 0-100
154 speed,
155 // Duration (0 is forever)
156 0,
157 // Command B
158 0,
159 // Command A
160 EVS.CONTROL_SPEED | EVS.CONTROL_GO
161 ];
162
163 state.ev3.write(state.shield, register, data);
164 }
165 }
166 },
167 setPin: {
168 value: function(pin, value) {
169 this.setPWM(this.pin, value);
170 }
171 },
172 validatePins: {
173 value: function() {
174 // Check for required pins
175 if (typeof this.opts.pin === "undefined") {
176 throw new Error("Pin must be defined");
177 }
178 }
179 }
180 },
181
182 GROVE_I2C_MOTOR_DRIVER: {
183 REGISTER: {
184 value: {
185 ADDRESS: 0x0F,
186 }
187 },
188 COMMANDS: {
189 value: {
190 SET_SPEED: 0x82,
191 SET_PWM_FREQUENCY: 0x84,
192 SET_DIRECTION: 0xAA,
193 NOOP: 0x01,
194 }
195 },
196
197 initialize: {
198 value: function(opts) {
199 var state = priv.get(this);
200 var shared = priv.get("GROVE_I2C_MOTOR_DRIVER");
201
202 if (!shared) {
203 shared = {
204 direction: {
205 A: 0x01,
206 B: 0x01,
207 },
208 speed: {
209 A: 0,
210 B: 0,
211 }
212 };
213
214 priv.set("GROVE_I2C_MOTOR_DRIVER", shared);
215 }
216
217 state.shared = shared;
218 state.pin = opts.pin.toUpperCase();
219
220 this.opts.pins = {
221 pwm: opts.pin,
222 dir: opts.pin,
223 };
224
225 this.address = opts.address || this.REGISTER.ADDRESS;
226
227 opts.address = this.address;
228
229 this.io.i2cConfig(opts);
230 }
231 },
232 setPWM: {
233 value: function(pin, value) {
234 var state = priv.get(this);
235 var speed = Board.constrain(value, 0, 255) | 0;
236
237 state.shared.speed[state.pin] = speed;
238
239 this.io.i2cWrite(this.address, [
240 this.COMMANDS.SET_SPEED,
241 state.shared.speed.A,
242 state.shared.speed.B,
243 ]);
244 }
245 },
246 setPin: {
247 value: function(pin, value) {
248 var state = priv.get(this);
249
250 // DIR_CCW = 0x02
251 // DIR_CW = 0x01
252 state.shared.direction[state.pin] = value ? 0x01 : 0x02;
253
254 var a = state.shared.direction.A & 0x03;
255 var b = state.shared.direction.B & 0x03;
256 var direction = (b << 2) | a;
257
258 this.io.i2cWrite(this.address, [
259 this.COMMANDS.SET_DIRECTION,
260 direction,
261 this.COMMANDS.NOOP,
262 ]);
263 }
264 },
265 validatePins: {
266 value: function() {
267 // Check for required pins
268 if (typeof this.opts.pin === "undefined") {
269 throw new Error("Pin must be defined");
270 }
271 }
272 }
273 }
274};
275
276// Aliases
277//
278// NXT motors have the exact same control commands as EV3 motors
279Controllers.EVS_NXT = Controllers.EVS_EV3;
280
281var Devices = {
282 NONDIRECTIONAL: {
283 pins: {
284 get: function() {
285 if (this.opts.pin) {
286 return {
287 pwm: this.opts.pin
288 };
289 } else {
290 return this.opts.pins || {};
291 }
292 }
293 },
294 dir: {
295 writable: true,
296 configurable: true,
297 value: function(speed) {
298 speed = speed || this.speed();
299 return this;
300 }
301 },
302 resume: {
303 value: function() {
304 var speed = this.speed();
305 this.speed({
306 speed: speed
307 });
308 return this;
309 }
310 }
311 },
312 DIRECTIONAL: {
313 pins: {
314 get: function() {
315 if (Array.isArray(this.opts.pins)) {
316 return {
317 pwm: this.opts.pins[0],
318 dir: this.opts.pins[1]
319 };
320 } else {
321 return this.opts.pins;
322 }
323 }
324 },
325 dir: {
326 writable: true,
327 configurable: true,
328 value: function(dir) {
329
330 this.stop();
331
332 this.setPin(this.pins.dir, dir.value);
333 this.direction = dir;
334
335 process.nextTick(this.emit.bind(this, dir.name));
336
337 return this;
338 }
339 }
340 },
341 CDIR: {
342 pins: {
343 get: function() {
344 if (Array.isArray(this.opts.pins)) {
345 return {
346 pwm: this.opts.pins[0],
347 dir: this.opts.pins[1],
348 cdir: this.opts.pins[2]
349 };
350 } else {
351 return this.opts.pins;
352 }
353 }
354 },
355 dir: {
356 value: function(dir) {
357
358 this.stop();
359 this.direction = dir;
360
361 this.setPin(this.pins.cdir, 1 ^ dir.value);
362 this.setPin(this.pins.dir, dir.value);
363
364 process.nextTick(this.emit.bind(this, dir.name));
365
366 return this;
367 }
368 },
369 brake: {
370 value: function(duration) {
371
372 this.speed({
373 speed: 0,
374 saveSpeed: false
375 });
376 this.setPin(this.pins.dir, 1, 127);
377 this.setPin(this.pins.cdir, 1, 128, 127);
378 this.speed({
379 speed: 255,
380 saveSpeed: false,
381 braking: true
382 });
383
384 process.nextTick(this.emit.bind(this, "brake"));
385
386 if (duration) {
387 var motor = this;
388 this.board.wait(duration, function() {
389 motor.stop();
390 });
391 }
392
393 return this;
394 }
395 }
396 }
397};
398
399/**
400 * Motor
401 * @constructor
402 *
403 * @param {Object} opts Options: pin|pins{pwm, dir[, cdir]}, device, controller, current
404 * @param {Number} pin A single pin for basic
405 * @param {Array} pins A two or three digit array of pins [pwm, dir]|[pwm, dir, cdir]
406 *
407 *
408 * Initializing "Hobby Motors"
409 *
410 * new five.Motor(9);
411 *
412 * ...is the same as...
413 *
414 * new five.Motor({
415 * pin: 9
416 * });
417 *
418 *
419 * Initializing 2 pin, Bi-Directional DC Motors:
420 *
421 * new five.Motor([ 3, 12 ]);
422 *
423 * ...is the same as...
424 *
425 * new five.Motor({
426 * pins: [ 3, 12 ]
427 * });
428 *
429 * ...is the same as...
430 *
431 * new five.Motor({
432 * pins: {
433 * pwm: 3,
434 * dir: 12
435 * }
436 * });
437 *
438 *
439 * Initializing 3 pin, I2C PCA9685 Motor Controllers:
440 * i.e. The Adafruit Motor Shield V2
441 *
442 * new five.Motor({
443 * pins: [ 8, 9, 10 ],
444 * controller: "PCA9685",
445 * address: 0x60
446 * });
447 *
448 *
449 * Initializing 3 pin, Bi-Directional DC Motors:
450 *
451 * new five.Motor([ 3, 12, 11 ]);
452 *
453 * ...is the same as...
454 *
455 * new five.Motor({
456 * pins: [ 3, 12, 11 ]
457 * });
458 *
459 * ...is the same as...
460 *
461 * new five.Motor({
462 * pins: {
463 * pwm: 3,
464 * dir: 12,
465 * cdir: 11
466 * }
467 * });
468 *
469 *
470 * Initializing Bi-Directional DC Motors with brake:
471 *
472 * new five.Motor({
473 * pins: {
474 * pwm: 3,
475 * dir: 12,
476 * brake: 11
477 * }
478 * });
479 *
480 *
481 * Initializing Bi-Directional DC Motors with current sensing pins:
482 * See Sensor.js for details on options
483 *
484 * new five.Motor({
485 * pins: [3, 12],
486 * current: {
487 * pin: "A0",
488 * freq: 250,
489 * range: [0, 2000]
490 * }
491 * });
492 *
493 *
494 * Initializing Bi-Directional DC Motors with inverted speed for reverse:
495 * Most likely used for non-commercial H-Bridge controllers
496 *
497 * new five.Motor({
498 * pins: [3, 12],
499 * invertPWM: true
500 * });
501 *
502 */
503
504function Motor(opts) {
505
506 var device, controller, state;
507
508 if (!(this instanceof Motor)) {
509 return new Motor(opts);
510 }
511
512 Board.Component.call(
513 this, this.opts = Board.Options(opts)
514 );
515
516 controller = opts.controller || null;
517
518 // Derive device based on pins passed
519 if (typeof this.opts.device === "undefined") {
520 this.opts.device = "DIRECTIONAL";
521
522 if (typeof this.opts.pins === "undefined" && typeof this.opts.register !== "object") {
523 this.opts.device = "NONDIRECTIONAL";
524 }
525
526 if (this.opts.pins) {
527 if (Array.isArray(this.opts.pins)) {
528 this.opts.device = ["NONDIRECTIONAL", "DIRECTIONAL", "CDIR"][this.opts.pins.length - 1];
529 } else {
530 if (typeof this.opts.pins.dir === "undefined") {
531 this.opts.device = "NONDIRECTIONAL";
532 } else {
533 this.opts.device = "DIRECTIONAL";
534 }
535 if (typeof this.opts.pins.cdir !== "undefined") {
536 this.opts.device = "CDIR";
537 }
538 }
539 }
540 }
541
542 if (typeof controller === "string" &&
543 (controller.startsWith("EVS") || controller.startsWith("GROVE_I2C"))) {
544 this.opts.device = "DIRECTIONAL";
545 }
546
547 // Allow users to pass in custom device types
548 device = typeof this.opts.device === "string" ?
549 Devices[this.opts.device] : this.opts.device;
550
551 this.threshold = typeof this.opts.threshold !== "undefined" ?
552 this.opts.threshold : 30;
553
554 this.invertPWM = typeof this.opts.invertPWM !== "undefined" ?
555 this.opts.invertPWM : false;
556
557 Object.defineProperties(this, device);
558
559 if (this.opts.register) {
560 this.opts.controller = "ShiftRegister";
561 }
562
563 /**
564 * Note: Controller decorates the device. Used for adding
565 * special controllers (i.e. PCA9685)
566 **/
567 if (this.opts.controller) {
568 controller = typeof this.opts.controller === "string" ?
569 Controllers[this.opts.controller] : this.opts.controller;
570
571 Board.Controller.call(this, controller, opts);
572 }
573
574 // current just wraps a Sensor
575 if (this.opts.current) {
576 this.opts.current.board = this.board;
577 this.current = new Sensor(this.opts.current);
578 }
579
580 // Create a "state" entry for privately
581 // storing the state of the motor
582 state = {
583 isOn: false,
584 currentSpeed: typeof this.opts.speed !== "undefined" ?
585 this.opts.speed : 128,
586 braking: false,
587 enabled: false
588 };
589
590 priv.set(this, state);
591
592 Object.defineProperties(this, {
593 // Calculated, read-only motor on/off state
594 // true|false
595 isOn: {
596 get: function() {
597 return state.isOn;
598 }
599 },
600 currentSpeed: {
601 get: function() {
602 return state.currentSpeed;
603 }
604 },
605 braking: {
606 get: function() {
607 return state.braking;
608 }
609 },
610 enabled: {
611 get: function() {
612 return state.enabled;
613 }
614 }
615 });
616
617 // We need to store and initialize the state of the dir pin(s)
618 this.direction = {
619 value: 1
620 };
621
622 if (this.initialize) {
623 this.initialize(opts);
624 }
625
626 this.validatePins();
627 this.enable();
628 this.dir(this.direction);
629}
630
631util.inherits(Motor, events.EventEmitter);
632
633Motor.prototype.initialize = function() {
634 this.io.pinMode(this.pins.pwm, this.io.MODES.PWM);
635
636 ["dir", "cdir", "brake", "enable"].forEach(function(pin) {
637 if (typeof this.pins[pin] !== "undefined") {
638 this.io.pinMode(this.pins[pin], this.io.MODES.OUTPUT);
639 }
640 }, this);
641
642};
643
644Motor.prototype.setPin = function(pin, value) {
645 this.io.digitalWrite(pin, value);
646};
647
648Motor.prototype.setPWM = function(pin, value) {
649 this.io.analogWrite(pin, __.map(value, 0, 255, 0, this.board.RESOLUTION.PWM));
650};
651
652Motor.prototype.speed = function(opts) {
653 var state = priv.get(this);
654
655 if (typeof opts === "undefined") {
656 return state.currentSpeed;
657 } else {
658
659 if (typeof opts === "number") {
660 opts = {
661 speed: opts
662 };
663 }
664
665 opts.speed = Board.constrain(opts.speed, 0, 255);
666
667 opts.saveSpeed = typeof opts.saveSpeed !== "undefined" ?
668 opts.saveSpeed : true;
669
670 if (opts.speed < this.threshold) {
671 opts.speed = 0;
672 }
673
674 state.isOn = opts.speed === 0 ? false : true;
675
676 if (opts.saveSpeed) {
677 state.currentSpeed = opts.speed;
678 }
679
680 if (opts.braking) {
681 state.braking = true;
682 }
683
684 if (this.invertPWM && this.direction.value === 1) {
685 opts.speed ^= 0xff;
686 }
687
688 this.setPWM(this.pins.pwm, opts.speed);
689
690 return this;
691 }
692
693};
694
695// start a motor - essentially just switch it on like a normal motor
696Motor.prototype.start = function(speed) {
697 // Send a signal to turn on the motor and run at given speed in whatever
698 // direction is currently set.
699 if (this.pins.brake && this.braking) {
700 this.setPin(this.pins.brake, 0);
701 }
702
703 // get current speed if nothing provided.
704 speed = typeof speed !== "undefined" ?
705 speed : this.speed();
706
707 this.speed({
708 speed: speed,
709 braking: false
710 });
711
712 // "start" event is fired when the motor is started
713 if (speed > 0) {
714 process.nextTick(this.emit.bind(this, "start"));
715 }
716
717 return this;
718};
719
720Motor.prototype.stop = function() {
721 this.speed({
722 speed: 0,
723 saveSpeed: false
724 });
725 process.nextTick(this.emit.bind(this, "stop"));
726
727 return this;
728};
729
730Motor.prototype.brake = function(duration) {
731 if (typeof this.pins.brake === "undefined") {
732 if (this.board.io.name !== "Mock") {
733 console.log("Non-braking motor type");
734 }
735 this.stop();
736 } else {
737 this.setPin(this.pins.brake, 1);
738 this.setPin(this.pins.dir, 1);
739 this.speed({
740 speed: 255,
741 saveSpeed: false,
742 braking: true
743 });
744 process.nextTick(this.emit.bind(this, "brake"));
745
746 if (duration) {
747 var motor = this;
748 this.board.wait(duration, function() {
749 motor.resume();
750 });
751 }
752 }
753
754 return this;
755};
756
757Motor.prototype.release = function() {
758 this.resume();
759 process.nextTick(this.emit.bind(this, "release"));
760
761 return this;
762};
763
764Motor.prototype.resume = function() {
765 var speed = this.speed();
766 this.dir(this.direction);
767 this.start(speed);
768
769 return this;
770};
771
772Motor.prototype.enable = function() {
773 var state = priv.get(this);
774 if (typeof this.pins.enable !== "undefined" && !state.enabled) {
775 this.setPin(this.pins.enable, 1);
776 state.enabled = true;
777 }
778};
779
780Motor.prototype.disable = function() {
781 var state = priv.get(this);
782 if (typeof this.pins.enable !== "undefined" && state.enabled) {
783 this.setPin(this.pins.enable, 0);
784 state.enabled = false;
785 }
786};
787
788// Check for required pins
789Motor.prototype.validatePins = function() {
790
791 if (typeof this.pins.pwm === "undefined") {
792 throw new Error("PWM pin must be defined");
793 }
794
795 if (typeof this.pins.dir === "undefined" && this.opts.device !== "NONDIRECTIONAL") {
796 throw new Error("DIR pin must be defined");
797 }
798
799 if (this.opts.device === "CDIR" && typeof this.pins.cdir === "undefined") {
800 throw new Error("CDIR pin must be defined for three wire motors");
801 }
802};
803
804[
805 /**
806 * forward Turn the Motor in its forward direction
807 * fwd Turn the Motor in its forward direction
808 *
809 * @param {Number} 0-255, 0 is stopped, 255 is fastest
810 * @return {Object} this
811 */
812 {
813 name: "forward",
814 abbr: "fwd",
815 value: 1
816 },
817 /**
818 * reverse Turn the Motor in its reverse direction
819 * rev Turn the Motor in its reverse direction
820 *
821 * @param {Number} 0-255, 0 is stopped, 255 is fastest
822 * @return {Object} this
823 */
824 {
825 name: "reverse",
826 abbr: "rev",
827 value: 0
828 }
829].forEach(function(dir) {
830 var method = function(speed) {
831 this.dir(dir);
832 this.start(speed);
833 return this;
834 };
835
836 Motor.prototype[dir.name] = Motor.prototype[dir.abbr] = method;
837});
838
839Motor.SHIELD_CONFIGS = {
840 ADAFRUIT_V1: {
841 M1: {
842 pins: {
843 pwm: 11
844 },
845 register: {
846 data: 8,
847 clock: 4,
848 latch: 12
849 },
850 bits: {
851 a: 2,
852 b: 3
853 }
854 },
855 M2: {
856 pins: {
857 pwm: 3
858 },
859 register: {
860 data: 8,
861 clock: 4,
862 latch: 12
863 },
864 bits: {
865 a: 1,
866 b: 4
867 }
868 },
869 M3: {
870 pins: {
871 pwm: 6
872 },
873 register: {
874 data: 8,
875 clock: 4,
876 latch: 12
877 },
878 bits: {
879 a: 5,
880 b: 7
881 }
882 },
883 M4: {
884 pins: {
885 pwm: 5
886 },
887 register: {
888 data: 8,
889 clock: 4,
890 latch: 12
891 },
892 bits: {
893 a: 0,
894 b: 6
895 }
896 }
897 },
898 ADAFRUIT_V2: {
899 M1: {
900 pins: {
901 pwm: 8,
902 dir: 9,
903 cdir: 10
904 },
905 address: 0x60,
906 controller: "PCA9685"
907 },
908 M2: {
909 pins: {
910 pwm: 13,
911 dir: 12,
912 cdir: 11
913 },
914 address: 0x60,
915 controller: "PCA9685"
916 },
917 M3: {
918 pins: {
919 pwm: 2,
920 dir: 3,
921 cdir: 4
922 },
923 address: 0x60,
924 controller: "PCA9685"
925 },
926 M4: {
927 pins: {
928 pwm: 7,
929 dir: 6,
930 cdir: 5
931 },
932 address: 0x60,
933 controller: "PCA9685"
934 }
935 },
936 SEEED_STUDIO: {
937 A: {
938 pins: {
939 pwm: 9,
940 dir: 8,
941 cdir: 11
942 }
943 },
944 B: {
945 pins: {
946 pwm: 10,
947 dir: 12,
948 cdir: 13
949 }
950 }
951 },
952 FREETRONICS_HBRIDGE: {
953 A: {
954 pins: {
955 pwm: 6,
956 dir: 4,
957 cdir: 7
958 }
959 },
960 B: {
961 pins: {
962 pwm: 5,
963 dir: 3,
964 cdir: 2
965 }
966 }
967 },
968 ARDUINO_MOTOR_SHIELD_R3_1: {
969 A: {
970 pins: {
971 pwm: 3,
972 dir: 12
973 }
974 },
975 B: {
976 pins: {
977 pwm: 11,
978 dir: 13
979 }
980 }
981 },
982 ARDUINO_MOTOR_SHIELD_R3_2: {
983 A: {
984 pins: {
985 pwm: 3,
986 dir: 12,
987 brake: 9
988 }
989 },
990 B: {
991 pins: {
992 pwm: 11,
993 dir: 13,
994 brake: 8
995 }
996 }
997 },
998 ARDUINO_MOTOR_SHIELD_R3_3: {
999 A: {
1000 pins: {
1001 pwm: 3,
1002 dir: 12,
1003 brake: 9,
1004 current: "A0"
1005 }
1006 },
1007 B: {
1008 pins: {
1009 pwm: 11,
1010 dir: 13,
1011 brake: 8,
1012 current: "A1"
1013 }
1014 }
1015 },
1016 DF_ROBOT: {
1017 A: {
1018 pins: {
1019 pwm: 6,
1020 dir: 7
1021 }
1022 },
1023 B: {
1024 pins: {
1025 pwm: 5,
1026 dir: 4
1027 }
1028 }
1029 },
1030 NKC_ELECTRONICS_KIT: {
1031 A: {
1032 pins: {
1033 pwm: 9,
1034 dir: 12
1035 }
1036 },
1037 B: {
1038 pins: {
1039 pwm: 10,
1040 dir: 13
1041 }
1042 }
1043 },
1044 RUGGED_CIRCUITS: {
1045 A: {
1046 pins: {
1047 pwm: 3,
1048 dir: 12
1049 }
1050 },
1051 B: {
1052 pins: {
1053 pwm: 11,
1054 dir: 13
1055 }
1056 }
1057 },
1058 SPARKFUN_ARDUMOTO: {
1059 A: {
1060 pins: {
1061 pwm: 3,
1062 dir: 12
1063 }
1064 },
1065 B: {
1066 pins: {
1067 pwm: 11,
1068 dir: 13
1069 }
1070 }
1071 },
1072 POLOLU_DRV8835_SHIELD: {
1073 M1: {
1074 pins: {
1075 pwm: 9,
1076 dir: 7
1077 }
1078 },
1079 M2: {
1080 pins: {
1081 pwm: 10,
1082 dir: 8
1083 }
1084 }
1085 },
1086 POLOLU_VNH5019_SHIELD: {
1087 M1: {
1088 pins: {
1089 pwm: 9,
1090 dir: 2,
1091 cdir: 4,
1092 enable: 6
1093 }
1094 },
1095 M2: {
1096 pins: {
1097 pwm: 10,
1098 dir: 7,
1099 cdir: 8,
1100 enable: 12
1101 }
1102 }
1103 },
1104 MICRO_MAGICIAN_V2: {
1105 A: {
1106 pins: {
1107 pwm: 6,
1108 dir: 8
1109 },
1110 invertPWM: true
1111 },
1112 B: {
1113 pins: {
1114 pwm: 5,
1115 dir: 7
1116 },
1117 invertPWM: true
1118 }
1119 },
1120 SPARKFUN_LUDUS: {
1121 A: {
1122 pins: {
1123 pwm: 3,
1124 dir: 4,
1125 cdir: 5
1126 }
1127 },
1128 B: {
1129 pins: {
1130 pwm: 6,
1131 dir: 7,
1132 cdir: 8
1133 }
1134 }
1135 },
1136 SPARKFUN_DUAL_HBRIDGE_EDISON_BLOCK: {
1137 A: {
1138 pins: {
1139 pwm: 20,
1140 dir: 33,
1141 cdir: 46,
1142 enable: 47
1143 }
1144 },
1145 B: {
1146 pins: {
1147 pwm: 14,
1148 dir: 48,
1149 cdir: 36,
1150 enable: 47
1151 }
1152 }
1153 },
1154
1155};
1156
1157
1158/**
1159 * Motors()
1160 * new Motors()
1161 */
1162function Motors(numsOrObjects) {
1163 if (!(this instanceof Motors)) {
1164 return new Motors(numsOrObjects);
1165 }
1166
1167 Object.defineProperty(this, "type", {
1168 value: Motor
1169 });
1170
1171 Collection.call(this, numsOrObjects);
1172}
1173
1174util.inherits(Motors, Collection);
1175
1176
1177/*
1178 * Motors, forward(speed)/fwd(speed)
1179 *
1180 * eg. array.forward(speed);
1181
1182 * Motors, reverse(speed)/rev(speed)
1183 *
1184 * eg. array.reverse(speed);
1185
1186 * Motors, start(speed)
1187 *
1188 * eg. array.start(speed);
1189
1190 * Motors, stop()
1191 *
1192 * eg. array.stop();
1193
1194 * Motors, brake()
1195 *
1196 * eg. array.brake();
1197
1198 * Motors, release()
1199 *
1200 * eg. array.release();
1201 */
1202
1203Collection.installMethodForwarding(
1204 Motors.prototype, Motor.prototype
1205);
1206
1207
1208// Assign Motors Collection class as static "method" of Motor.
1209// TODO: Eliminate .Array for 1.0.0
1210Motor.Array = Motors;
1211Motor.Collection = Motors;
1212
1213/* istanbul ignore else */
1214if (!!process.env.IS_TEST_MODE) {
1215 Motor.Controllers = Controllers;
1216 Motor.purge = function() {
1217 priv.clear();
1218 registers.clear();
1219 };
1220}
1221
1222module.exports = Motor;