Module: j5e/animation

Description

The j5e Animation module handles tweening between a series of key frames. It works with with the LED, RGB, and Servo classes, and can be used to create complex scripted animations like those found in theme park animatronics. In addition to simple, single value animations, you can also use the `j5e/animation` module to create complex animations using tuples to represent coordinates in a 3d space. For positioning joints in that space you will need an inverse kinematics solver such as tharp.

Inbetweening, also commonly known as tweening, is a process in animation that involves generating intermediate frames, called inbetweens, between two keyframes. The intended result is to create the illusion of movement by smoothly transitioning one image into another.Read more on Wikipedia

A key frame in animation and filmmaking is a drawing or shot that defines the starting and ending points of any smooth transition. These are called frames because their position in time is measured in frames on a strip of film or on a digital video editing timeline. A sequence of key frames defines which movement the viewer will see, whereas the position of the key frames on the film, video, or animation defines the timing of the movement. Because only two or three key frames over the span of a second do not create the illusion of movement, the remaining frames are filled with "inbetweens".Read more on Wikipedia

Animatronics refers to mechatronic puppets. They are a modern variant of the automaton and are often used for the portrayal of characters in films and in theme park attractions.Read more on Wikipedia

In geometry, a coordinate system is a system that uses one or more numbers, or coordinates, to uniquely determine the position of the points or other geometric elements on a manifold such as Euclidean space. The order of the coordinates is significant, and they are sometimes identified by their position in an ordered tuple and sometimes by a letter, as in "the x-coordinate". The coordinates are taken to be real numbers in elementary mathematics, but may be complex numbers or elements of a more abstract system such as a commutative ring. The use of a coordinate system allows problems in geometry to be translated into problems about numbers and vice versa; this is the basis of analytic geometry.Read more on Wikipedia

In computer animation and robotics, inverse kinematics is the mathematical process of calculating the variable joint parameters needed to place the end of a kinematic chain, such as a robot manipulator or animation character's skeleton, in a given position and orientation relative to the start of the chain. Given joint parameters, the position and orientation of the chain's end, e.g. the hand of the character or robot, can typically be calculated directly using multiple applications of trigonometric formulas, a process known as forward kinematics. However, the reverse operation is, in general, much more challenging.Read more on Wikipedia

Requires


Class: Animation

Allows for scripted control of LEDs, RGBs, and Servos

Constructor

new Animation(target)

Parameters

Name
Type
Description
target
(required)
Object, or Array.<Object>

Description:
Device (LED, RGB, or Servo) or an array of devices to be animated (See instantiation for more information)

Example

// 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);

Events

  • animation:pause - Emmited when the animation is paused by the pause() method
  • animation:stop - Emmited whtn then animation is stopped by the stop() method,event: or when there are no more segments to play

Methods

Animation.enqueue

Add an animation segment to the animation queue (See animation for more information)

animation.enqueue(options);

Parameters

Name
Type
Description
options
(required)
object

Description:
Animation segment options

options.keyFrames
(required)
Array.<object>

Description:
Values for each cuepoint

options.cuePoints
Array.<number>

Description:
Segment cuepoints from 0-1
Default: [0, 1]

options.duration
number

Description:
Duration of segment in ms
Default: 1000

options.easing
fuction

Description:
Easing function to use for segment
Default: linear()

options.loop
boolean

Description:
If true the segment will loop back

options.loopback
number

Description:
The time to loop back to [0-1]
Default: 0

options.metronomic
boolean

Description:
Instead of looping back to the beginning it will reverse direction at the end of the segment

options.currentSpeed
number

Description:
The playback speed [0-1]
Default: 1

options.progress
number

Description:
The current progress

options.fps
number

Description:
Frames per second
Default: 50

options.rate
number

Description:
ms between frames
Default: 20

options.paused
boolean

Description:
Wether the animation is in a paused state

options.onstart
function

Description:
Function to call when the segment starts

options.onpause
function

Description:
Function to call when the segment is paused

options.onstop
function

Description:
Function to call when the segment is stopped

options.oncomplete
function

Description:
Function to call when the segment is complete

options.onloop
function

Description:
Function to call when the segment loops

Example

//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);

Animation.play

Resume play on an animation after it has been paused or stopped.

animation.play();

Returns: Animation

Example

// 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);

Animation.pause

Pause animation while maintaining progress, speed and segment queue

animation.pause();

Returns: Animation

Example

// 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);

Animation.stop

Stop the animation, flushing the segment queue

animation.stop();

Returns: Animation

Example

// 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);

Animation.speed

Get or set the current playback speed

animation.speed(speed);

Returns: Animation

Parameters

Name
Type
Description
speed
Number

Description:
The desired playback speed (1 = normal)

Example

// 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);

Animation.on

Create an event listener

animation.on(event, listener);

Parameters

Name
Type
Description
event
(required)
string

Description:
The name of the event to listen for

listener
(required)
function

Description:
A callback to run when the event is fired.


Animation.removeListener

Remove an event listener

animation.removeListener(event, listener);

Parameters

Name
Type
Description
event
(required)
string

Description:
The name of the event that we are removing a listener from

listener
(required)
function

Description:
The callback that we are removing


Animation.emit

Note: This method is not part of the public API, and is subject to change.

Emit an event

animation.emit(event);

Parameters

Name
Type
Description
event
(required)
string

Description:
The name of the event to emit


Animation.once

Create an event listener that will only fire one time.

animation.once(event, listener);

Parameters

Name
Type
Description
event
(required)
string

Description:
The name of the event to listen for

listener
(required)
function

Description:
A callback to run when the event is fired.