Language: EN

libreria-arduino-articulated

Arduino Articulated Library

The Articulated library implements the necessary calculations to solve an articulated triangle or quadrilateral in 2D or 3D. They are designed to simplify the control of articulated robots (robotic arms, quadrupeds, hexapods, bipeds…)

User manual

Each type of polygon object is instantiated through its corresponding constructor (ArticulatedTriangle2D, ArticulatedTriangle3D, ArticulatedQuadrilateral2D, ArticulatedQuadrilateral3D) which receives the lengths of the arms that form each articulated polygon.

Additionally, the UseInnerRelativeAngles parameter defines if we want the relative angles between segments to be interior or exterior. By default, they are exterior. The library works in radians.

The Articulated library has functions for solving the direct kinematics (SolveDirectAbsolute and SolveDirectRelative) or inverse kinematics (SolveReverse).

The SolveDirectAbsolute function considers the angles of the segments with respect to the ground plane, while the SolveDirectRelative considers the angle of one segment with respect to the previous one. Normally we will work with SolveDirectRelative.

On the other hand, the functions of SolveReverse for quadrilaterals require passing as a parameter the absolute angle of the last segment, since the resolution of the position with the lengths admits multiple solutions.

Articulated 2D Triangle

Constructor

ArticulatedTriangle2D(float l1, float l2, bool useInnerRelativeAngles = false)

Use of ArticulatedTriangle2D

void SolveDirectAbsolute(float angle1, float angle2);
void SolveDirectRelative(float angle1, float angle2);

void SolveReverse();
void SolveReverse(Point2D target);

bool UseInnerRelativeAngles;
float L1, L2, D;
float AbsoluteAngle1, AbsoluteAngle2, RelativeAngle12;
Point2D Target;

Articulated 2D Quadrilateral

Constructor

ArticulatedQuadrilateral2D(float l1, float l2, float l3, bool useInnerRelativeAngles = false) 

Use of ArticulatedQuadrilateral2D

void SolveDirectAbsolute(float angle1, float angle2, float angle3);
void SolveDirectRelative(float angle1, float angle2, float angle3);

void SolveReverse(float absoluteAngle3);
void SolveReverse(Point2D target, float absoluteAngle3);

bool UseInnerRelativeAngles;
float L1, L2, L3, D;
float AbsoluteAngle1, AbsoluteAngle2, AbsoluteAngle3, RelativeAngle12, RelativeAngle23;
Point2D Target;

Articulated 3D Triangle

Constructor

ArticulatedTriangle3D(float l1, float l2, bool useInnerRelativeAngles = false)

Use of ArticulatedTriangle3D

void SolveDirectAbsolute(float angle0, float angle1, float angle2);
void SolveDirectRelative(float angle0, float angle1, float angle2);

void SolveReverse();
void SolveReverse(Point3D target);

bool UseInnerRelativeAngles;
float L1, L2, D;
float AbsoluteAngle0, AbsoluteAngle1, AbsoluteAngle2, RelativeAngle12;
Point3D Target;

Articulated 3D Quadrilateral

Constructor

ArticulatedQuadrilateral3D(float l1, float l2, float l3, bool useInnerRelativeAngles = false)

Use of ArticulatedQuadrilateral3D

void SolveDirectAbsolute(float angle0, float angle1, float angle2, float angle3);
void SolveDirectRelative(float angle0, float angle1, float angle2, float angle3);

void SolveReverse(float absoluteAngle3);
void SolveReverse(Point3D target, float absoluteAngle3);

bool UseInnerRelativeAngles;
float L1, L2, L3, D;
float AbsoluteAngle0, AbsoluteAngle1, AbsoluteAngle2, AbsoluteAngle3, RelativeAngle12, RelativeAngle23;
Point3D Target;

Examples

The Articulated library includes the following examples to illustrate its use.

  • Triangle2D: Example that shows how to create a swaying effect with AsyncServo
#include "ArticulatedTriangle2D.h"

ArticulatedTriangle2D trig(100, 50, false);

void Debug(ArticulatedTriangle2D& tri)
{
  Serial.print("Target X:\t");
  Serial.println(tri.Target.X, 4);
  Serial.print("Target Y:\t");
  Serial.println(tri.Target.Y, 4);

  Serial.print("Abs. Angle1:\t");
  Serial.println(degrees(tri.AbsoluteAngle1), 4);
  Serial.print("Abs. Angle2:\t");
  Serial.println(degrees(tri.AbsoluteAngle2), 4);

  Serial.print("Rel. Angle12:\t");
  Serial.println(degrees(tri.RelativeAngle12), 4);
}

void setup()
{
  Serial.begin(115200);
  while (!Serial) { ; }

  Serial.println(F("**** TRIG2D ****"));
  Serial.println(F("Solve Direct Absolute"));
  trig.SolveDirectAbsolute(radians(55), radians(-20));
  Debug(trig);

  Serial.println(F("Solve Direct Relative"));
  trig.SolveDirectRelative(radians(55), radians(-75));
  Debug(trig);

  Serial.println(F("Solve Inverse"));
  trig.Target.X = 104.3423;
  trig.Target.Y = 64.8141;
  trig.SolveReverse();
  Debug(trig);
}

void loop()
{
  // Do nothing
  delay(10000);
}
  • Quadrilateral2D: Example that shows the use for an articulated 2D quadrilateral
#include "ArticulatedQuadrilateral2D.h"

ArticulatedQuadrilateral2D quad(100, 50, 30, false);

void Debug(ArticulatedQuadrilateral2D& qua)
{
  Serial.print("Target X:\t");
  Serial.println(qua.Target.X, 4);
  Serial.print("Target Y:\t");
  Serial.println(qua.Target.Y, 4);

  Serial.print("Abs. Angle 1:\t");
  Serial.println(degrees(qua.AbsoluteAngle1), 4);
  Serial.print("Abs. Angle 2:\t");
  Serial.println(degrees(qua.AbsoluteAngle2), 4);
  Serial.print("Abs. Angle 3:\t");
  Serial.println(degrees(qua.AbsoluteAngle3), 4);

  Serial.print("Rel. Angle 12:\t");
  Serial.println(degrees(qua.RelativeAngle12), 4);
  Serial.print("Rel. Angle 23:\t");
  Serial.println(degrees(qua.RelativeAngle23), 4);
}

void setup()
{
  Serial.begin(115200);
  while (!Serial) { ; }

  Serial.println(F("**** QUAD2D ****"));
  Serial.println(F("Solve Direct Absolute"));
  quad.SolveDirectAbsolute(radians(55), radians(-20), radians(-70));
  Debug(quad);

  Serial.println(F("Solve Direct Relative"));
  quad.SolveDirectRelative(radians(55), radians(-75), radians(-50));
  Debug(quad);

  Serial.println(F("Solve Inverse"));
  quad.Target.X = 114.60289;
  quad.Target.Y = 36.62342;
  quad.SolveReverse(radians(-70));
  Debug(quad);
}

void loop()
{
  // Do nothing
  delay(10000);
}
  • Triangle3D: Example that shows the use for a 3D articulated triangle
#include "ArticulatedTriangle3D.h"

ArticulatedTriangle3D trig3D(100, 50, false);

void Debug(ArticulatedTriangle3D& tri)
{
  Serial.print("Target X:\t");
  Serial.println(tri.Target.X, 4);
  Serial.print("Target Y:\t");
  Serial.println(tri.Target.Y, 4);
  Serial.print("Target Z:\t");
  Serial.println(tri.Target.Z, 4);

  Serial.print("Abs. Angle0:\t");
  Serial.println(degrees(tri.AbsoluteAngle0), 4);
  Serial.print("Abs. Angle1:\t");
  Serial.println(degrees(tri.AbsoluteAngle1), 4);
  Serial.print("Abs. Angle2:\t");
  Serial.println(degrees(tri.AbsoluteAngle2), 4);

  Serial.print("Rel. Angle12:\t");
  Serial.println(degrees(tri.RelativeAngle12), 4);
}

void setup()
{
  Serial.begin(115200);
  while (!Serial) { ; }

  Serial.println(F("**** TRIG3D ****"));
  Serial.println(F("Solve Direct Absolute"));
  trig3D.SolveDirectAbsolute(radians(30), radians(55), radians(-20));
  Debug(trig3D);

  Serial.println(F("Solve Direct Relative"));
  trig3D.SolveDirectRelative(radians(30), radians(55), radians(-75));
  Debug(trig3D);

  Serial.println(F("Solve Inverse"));
  trig3D.Target.X = 90.3631;
  trig3D.Target.Y = 52.1711;
  trig3D.Target.Z = 64.8141;
  trig3D.SolveReverse();
  Debug(trig3D);
}

void loop()
{
  // Do nothing
  delay(10000);
}
  • Quadrilateral3D: Example that shows the use for a 3D articulated quadrilateral
#include "ArticulatedQuadrilateral3D.h"

ArticulatedQuadrilateral3D quad3D(100, 50, 30, false);

void Debug(ArticulatedQuadrilateral3D& qua)
{
  Serial.print("Target X:\t");
  Serial.println(qua.Target.X, 4);
  Serial.print("Target Y:\t");
  Serial.println(qua.Target.Y, 4);
  Serial.print("Target Z:\t");
  Serial.println(qua.Target.Z, 4);

  Serial.print("Abs. Angle 0:\t");
  Serial.println(degrees(qua.AbsoluteAngle0), 4);
  Serial.print("Abs. Angle 1:\t");
  Serial.println(degrees(qua.AbsoluteAngle1), 4);
  Serial.print("Abs. Angle 2:\t");
  Serial.println(degrees(qua.AbsoluteAngle2), 4);
  Serial.print("Abs. Angle 3:\t");
  Serial.println(degrees(qua.AbsoluteAngle3), 4);

  Serial.print("Rel. Angle 12:\t");
  Serial.println(degrees(qua.RelativeAngle12), 4);
  Serial.print("Rel. Angle 23:\t");
  Serial.println(degrees(qua.RelativeAngle23), 4);
}

void setup()
{
  Serial.begin(115200);
  while (!Serial) { ; }
  
  Serial.println(F("**** QUAD3D ****"));
  Serial.println(F("Solve Direct Absolute"));
  quad3D.SolveDirectAbsolute(radians(30), radians(55), radians(-20), radians(-70));
  Debug(quad3D);

  Serial.println(F("Solve Direct Relative"));
  quad3D.SolveDirectRelative(radians(30), radians(55), radians(-75), radians(-50));
  Debug(quad3D);

  Serial.println(F("Solve Inverse"));
  quad3D.Target.X = 99.2490;
  quad3D.Target.Y = 57.3014;
  quad3D.Target.Z = 36.62342;
  quad3D.SolveReverse(radians(-70));
  Debug(quad3D);
}

void loop()
{
  // Do nothing
  delay(10000);
}

Installation

  • Download the latest version from GitHub
  • Unzip the file
  • Copy to your libraries folder (usually My Documents\Arduino\libraries)
  • Restart the Arduino IDE

github-full