new Animation( target )

Description
Allows for scripted control of LEDs, RGBs, and Servos
Parameters
Name Type Description
target LED | Array.<LED> | RGB | Array.<RGB> | Servo | Array.<Servo> LEDs, RGBs, and/or Servos to be animated (See j5e's Timeline and Tweening Tools for more information)
Examples

Make a servo "wave"

import Servo from "j5e/servo";
			import Animation from "j5e/animation";
			
			const servo = await new Servo(13);
			const ani = await new Animation(servo);
			
			const wave = {
			  duration: 4000,
			  cuePoints: [0,  0.375, 0.625, 1],
			  keyFrames: [0, 135, 45, 180],
			  loop: true,
			  metronomic: true
			};
			
			ani.enqueue(wave);
Fires

Methods


on( event, listener )

Description
Create an event listener
Parameters
Name Type Description
event string The name of the event to listen for
listener function A callback to run when the event is fired.

removeListener( event, listener )

Description
Remove an event listener
Parameters
Name Type Description
event string The name of the event that we are removing a listener from
listener function The callback that we are removing

once( event, listener )

Description
Create an event listener that will only fire one time.
Parameters
Name Type Description
event string The name of the event to listen for
listener function A callback to run when the event is fired.

enqueue( options )

Description
Add an animation segment to the animation queue (See j5e's Timeline and Tweening Tools for more information)
Parameters
Name Type Description
options object Animation segment options
Name Type Attributes Default Description
keyFrames Array.<object> Values for each cuepoint
cuePoints Array.<number> <optional>
[0, 1] Segment cuepoints from 0-1
duration number <optional>
1000 Duration of segment in ms
easing fuction <optional>
linear() Easing function to use for segment
loop boolean <optional>
false If true the segment will loop back
loopback number <optional>
0 The time to loop back to [0-1]
metronomic boolean <optional>
false Instead of looping back to the beginning it will reverse direction at the end of the segment
currentSpeed number <optional>
1 The playback speed [0-1]
progress number <optional>
The current progress
fps number <optional>
50 Frames per second
rate number <optional>
20 ms between frames
paused boolean <optional>
false Wether the animation is in a paused state
onstart function <optional>
Function to call when the segment starts
onpause function <optional>
Function to call when the segment is paused
onstop function <optional>
Function to call when the segment is stopped
oncomplete function <optional>
Function to call when the segment is complete
onloop function <optional>
Function to call when the segment loops
Examples

Make a servo "wave"

import Servo from "j5e/servo";
			import Animation from "j5e/animation";
			
			const servo = await new Servo(13);
			const ani = await new Animation(servo);
			
			const wave = {
			  duration: 4000,
			  cuePoints: [0,  0.375, 0.625, 1],
			  keyFrames: [0, 135, 45, 180],
			  loop: true,
			  metronomic: true
			};
			
			ani.enqueue(wave);
Details

play()

Description
Resume play on an animation after it has been paused or stopped.
Returns
Animation
Examples

Make a servo "wave" for five seconds, pause for one second and then resume waving

import Servo from "j5e/servo";
			import Animation from "j5e/animation";
			import {timer} from "j5e/fn";
			
			const servo = await new Servo(13);
			const ani = await new Animation(servo);
			
			const wave = {
			  duration: 4000,
			  cuePoints: [0,  0.375, 0.625, 1],
			  keyFrames: [0, 135, 45, 180],
			  loop: true,
			  metronomic: true
			};
			
			ani.enqueue(wave);
			
			timer.setTimeout(function() {
			  ani.pause();
			}, 5000);
			
			timer.setTimeout(function() {
			  ani.play();
			}, 6000);
Details

pause()

Description
Pause animation while maintaining progress, speed and segment queue
Returns
Animation
Examples

Make a servo "wave" for five seconds, pause for one second and then resume waving

import Servo from "j5e/servo";
			import Animation from "j5e/animation";
			import {timer} from "j5e/fn";
			
			const servo = await new Servo(13);
			const ani = await new Animation(servo);
			
			const wave = {
			  duration: 4000,
			  cuePoints: [0,  0.375, 0.625, 1],
			  keyFrames: [0, 135, 45, 180],
			  loop: true,
			  metronomic: true
			};
			
			ani.enqueue(wave);
			
			timer.setTimeout(function() {
			  ani.pause();
			}, 5000);
			
			timer.setTimeout(function() {
			  ani.play();
			}, 6000);
Details

stop()

Description
Stop the animation, flushing the segment queue
Returns
Animation
Examples

Make a servo "wave" for five seconds and then stop, flushing the queue

import Servo from "j5e/servo";
			import Animation from "j5e/animation";
			import {timer} from "j5e/fn";
			
			const servo = await new Servo(13);
			const ani = await new Animation(servo);
			
			const wave = {
			  duration: 4000,
			  cuePoints: [0,  0.375, 0.625, 1],
			  keyFrames: [0, 135, 45, 180],
			  loop: true,
			  metronomic: true
			};
			
			ani.enqueue(wave);
			
			timer.setTimeout(function() {
			  ani.stop();
			}, 5000);
Details

speed( [ speed ] )

Description
Get or set the current playback speed
Parameters
Name Type Attributes Description
speed Number <optional>
The desired playback speed (1 = normal)
Returns
Animation
Examples

Make a servo "wave" for one second, increase the speed, wait another second and decrease the speed for one second and then stop.

import Servo from "j5e/servo";
			import Animation from "j5e/animation";
			import {timer} from "j5e/fn";
			
			const servo = await new Servo(13);
			const ani = await new Animation(servo);
			
			const wave = {
			  duration: 4000,
			  cuePoints: [0,  0.375, 0.625, 1],
			  keyFrames: [0, 135, 45, 180],
			  loop: true,
			  metronomic: true
			};
			
			ani.enqueue(wave);
			
			timer.setTimeout(function() {
			  ani.speed(2.0); // Speed up to 2x
			}, 1000);
			
			timer.setTimeout(function() {
			  ani.speed(0.5); // Speed up to 1/2x
			}, 2000);
			
			timer.setTimeout(function() {
			  ani.stop(); // Note, animation speed is still 0.5
			}, 3000);
Details