Skip to content
Donovan Buck edited this page Dec 7, 2015 · 9 revisions

Chain Contructor

Grabbers Robots

new Tharp.Chain(opts)

A Tharp chain will Wrap the actuators so that we have all the info and methods we need to define and solve for our the kinematic chain.

@param {Object} opts Options

  • opts.actuators {Servos, Servo.Array, Array of Servo Objects, or a Servos initialization array} The object or device array that contains the chain's actuators, or an array of Servo opts to create a new Servos() object [Required]
  • opts.chainType {String}: One of the pre-defined leg types described in the readme. Don't see your system type? Open an issue, or better yet make a Pull Request! [Required]
  • opts.links {Array}: An array with the link lengths of our system. [Required]
  • opts.origin {Array} [x, y, z]: The x, y and z offset of the chain's origin point from the robot's origin point. [Optional. Default: [0, 0, 0] ]
  • opts.startAt {Array} [x, y, z]: The initial x, y and z position of the chain's end effector. [Optional. Default: [0, 0, 0] ]
  • opts.require {Boolean}: If true then calls to Robot.render() will error if this chain cannot be solved for the given position. [Optional. Default: true]

returns this Chain()

Example:

var frontRight = new tharp.Chain({
  actuators: [
    {pin:40, offset: 24, startAt: 0, range: [0, 90] },
    {pin:39, offset: 87, startAt: 78, range: [-80, 78] },
    {pin:38, offset: 165, invert: true, startAt: -140, range: [-160, -10] }
  ],
  chainType: "ZYY",
  origin: [4.25, 2.875, 8.15],
  links: [1.25, 7.6125, ]
});

Chain Methods

Chain.render(opts)

Move all the servos so the end effector is at the target position. In most cases you would want to call Chain.solve() on all your chains and make sure they can all reach the desired end effector position before rendering the movement. Tharp.Robot can handle this extra step for you so you should not need to use Chain.render() directly.

@param {Array} opts Options: {[position]}

  • opts.position {Array}: The desired position of the end effector in 3D coordinate space [Optional].

returns this Chain()

Example:

frontRight.render({
  position: [ 12.5, -4, 8.2 ]
});

Chain.solve(opts)

Find the angles needed to position the end effector at a desired point. The angles are written to chain.position.

@param {Object} opts Options: {[position]}

  • opts.position {Array}: The desired position of the end effector in global coordinate space [Optional].

Returns array of angles (in radians) or position

Example:

var angles = frontRight.solve({
  position: [ 12.5, -4, 8.2 ]
});
// returns [0.4, -0.2, 0.8]

Chain.eePosition

Find an end effector's position relative to the kinematic chain origin

  • @param {Object} opts Options: {position[, origin][, orientation] }
  • opts.position {Array} position: The end effector position in global coordinate space [optional]
  • opts.origin {Array}: origin: The kinematic chain origin relative to the robots origin point
  • opts.orientation {Object}: orientation: {[pitch][, roll][, yaw]} pitch, roll and yaw given in radians

returns a vector [x, y, z]

Example:

var offset = frontRight.eePosition({
  position: [ 12.5, -4, 8.2 ]
});
// returns [ 8.25, -1.125, 0.05]

Chain Properties

Chain.position {Array} [x, y, z]

The end effector position in global coordinate space.

Clone this wiki locally