Skip to content

IndySDK API Documentation

IndySDK comes with a range of functions dedicated to kinematics and dynamics computations, essential for controlling the robot. For more information, refer to "AbstractRobotXD" located within the directory "../NRMKFramework/Indy/Model".

This documentation offers a concise overview of the APIs, organized into various categories.

General Conventions

Vector Representation

  • [\omega^T, v^T]^T

Units

  • Position: meters (m)
  • Orientation: radians (rad)
  • Force: Newtons (N)
  • Torque: Newton-meters (Nm)

Frame References

  • Reference Frame: Default is set to the robot base.
  • Target Frame: Default is set to the end-effector / last body frame.

1. Kinematics APIs

The following kinematics related functions are provide in the IndySDK for calculating and managing the motion and configuration of robots. These functions are designed to facilitate precise control and motion analysis.

1.1. Forward Kinematics

AbstractRobotXD::computeFK

This method computes the task position and, optionally, the task velocity based on the robot's current pose.

void computeFK(TaskPosition &pos)
void computeFK(TaskPosition &pos, TaskVelocity &vel)
  • Parameters
    • TaskPosition &pos: Represents the task position, which is derived from a homogeneous transformation (LieGroup::HTransform).
    • TaskVelocity &vel (Optional): Represents the task velocity, derived from a twist (LieGroup::Twist).

1.2. Jacobian

AbstractRobotXD::computeJacobian

Definition and Configuration:

  • The Task Jacobian matrix represents the relationship between the task spave velocities and the joint velocities. Its definition depends on the specified target and reference frames (which default to the end-effector and robot base frames, respectively).

This function calculates the task position, task velocity, task Jacobian, and the derivative of the task Jacobian, providing essential information for dynamic and control computations.

void computeJacobian(TaskPosition &pos, TaskVelocity &vel, TaskJacobian &J, TaskJacobian &Jdot)
  • Parameters
    • TaskPosition &pos: Constructs a task position from a homogeneous transformation (LieGroup::HTransform).
    • TaskVelocity &vel: Constructs a task velocity from a twist (LieGroup::Twist).
    • TaskJacobian &J: The task Jacobian, represented as a 6x6 matrix (Eigen::Matrix).
    • TaskJacobian &Jdot: The time derivative of the Task Jacobian.

2. Robot Dynamics APIs

IndySDK offers a variety of functions for inverse dynamics calculations, including a specialized passivity-based recursive Newton-Euler method. IndySDK also includes function for computing robot dynamics, such as the inertia matrix, Coriolis and centrifugal matrix, and gravity vector. This section provides an overview of related APIs.

2.1. Inverse Dynamics

AbstractRobotXD::idyn

This function implements the recursive Newton-Euler method (gravity is optional) for a grounded system for a given joint velocity and acceleration vector.

void idyn(JointVec const & qdot, JointVec const & qddot)
void idyn(JointVec const & qdot, JointVec const & qddot, LieGroup::Vector3D const & gacc)
  • Parameters
    • JointVec const &qdot: Joint velocity vector.
    • JointVec const &qddot: Joint acceleration vector.
    • LieGroup::Vector3D const &gacc (Optional): Gravity acceleration vector.

2.2. Passive Inverse Dynamics

AbstractRobotXD::idyn_passive

This function implements the recursive passivity-based Newton-Euler method (gravity is optional) for a grounded system for a given joint velocity and acceleration vector

void idyn_passive(JointVec const &qdot, JointVec const &qddot)
void idyn_passive(JointVec const &qdot, JointVec const &qddot, LieGroup::Vector3D const &gacc)
  • Parameters
    • JointVec const &qdot: Joint reference velocity vector.
    • JointVec const &qddot: Joint acceleration vector.
    • LieGroup::Vector3D const &gacc (Optional): Gravity acceleration vector.

2.3. Gravity

AbstractRobotXD::idyn_gravity

This function implements the recursive Newton-Euler method for gravitational effects only, applicable to both grounded and floating systems at a given joint position..

void idyn_gravity(LieGroup::Vector3D const &gacc)
  • Parameters
    • LieGroup::Vector3D const &gacc: Gravity acceleration vector.

2.4. Momentum

AbstractRobotXD::idyn_momentum

This function uses a specified joint acceleration vector to calculate the momentum of a grounded system using the recursive Newton-Euler method.

void idyn_momentum(JointVec const &qddot)
  • Parameters
    • JointVec const &qddot: Joint acceleration vector.

2.5. Dynamics Parameters

AbstractRobotXD::computeDynamicsParams

This function calculates dynamic parameters including the inertia matrix, Coriolis and centrifugal matrix, and gravity force vector for a given gravity force direction.

void computeDynamicsParams(LieGroup::Vector3D const &gravDir, JointMat &M, JointMat &C, JointVec &G)
  • Parameters
    • LieGroup::Vector3D const &gravDir: Direction of gravity force.
    • JointMat &M: Inertia matrix.
    • JointMat &C: Coriolis and centrifugal matrix.
    • JointVec &G: Gravity force vector.

3. H-infinity Controller APIs

Neuromeka provides a built-in position controller for users of IndySDK. This section highlights the available APIs to use this special type of position controller, called the \mathcal{H}_\infty optimal controller, both for joint space and task space control. In the \mathcal{H}_\infty optimal controller, there are mainly two terms, feedforward and feedback terms. Feedforward term is calculated from the reference velocity (\dot{q}_{ref}) and robot model. The feedback term is added to attenuate the disturbances and model uncertainties in the sense of \mathcal{H}_\infty optimality.

\tau = \widehat{M}(q)\ddot{q}_{\text{ref}} + \widehat{C}(q,\dot{q})\dot{q}_{\text{ref}} + \widehat{g}(q) + K\dot{e}_{\text{ref}},

where \widehat{M}, \widehat{C}, and \widehat{g} denote the inertia matrix, Coriolis matrix, and gravity vector, respectively. The reference velocity errors can be computed as follows, \dot{e}_{\text{ref}} = \dot{q}_{\text{ref}} - \dot{q}. The reference acceleration (\ddot{q}_{\text{ref}}) is defined as follows.

\ddot{q}_{\text{ref}} = \ddot{q}_{\text{des}} + K_{v}\dot{e} + K_{p}e,\quad \dot{q}_{\text{ref}} = \dot{q}_{\text{des}} + K_{v}e + K_{p}\int{e},

where e = q_{\text{des}} - q, is the joint position error and q_{\text{des}} is the desired position trajectory. K, K_{v}, K_{p} are control gains.

For further insight, we direct the reader to the comprehensive analysis presented in the paper below.

3.1. Initialize H-Infinity Controller

AbstractRobotXD::initHinfController

This function initializes the H-infinity controller with a specified control period for integral error computation purposes, and sets pasivity-based inverse dynamics.

void initHinfController(double delt)
  • Parameters
    • double delt: Control period.

3.2. Reset H-Infinity Controller

AbstractRobotXD::resetHinfController

This function resets the integral errors within the H-infinity controller.

void resetHinfController()
  • Parameters
    • None

3.3. Set H-Infinity Control Gains

AbstractRobotXD::setHinfControlGain

This function configures the gain parameters for the H-infinity controller for the specified controller.

void setHinfControlGain(const JointVec &kp, const JointVec &kv, const JointVec &ki, const int &mode)
  • Parameters
    • const JointVec &kp: Position gain vector.
    • const JointVec &kv: Damping gain vector.
    • const JointVec &ki: Integral gain vector.
    • const int &mode: Control mode (0 for joint control, 1 for task control).

3.4. H-Infinity Controller for Joint Space Control

AbstractRobotXD::HinfController

This function computes the desired torque for joint space control based on the desired joint position, velocity, and acceleration, considering the robot's current state.

void HinfController(LieGroup::Vector3D const &grav, JointVec const &qd, JointVec const &qdotd, JointVec const &qddotd)
  • Parameters
    • LieGroup::Vector3D const &grav: Gravity force direction.
    • JointVec const &qd: Desired joint position vector.
    • JointVec const &qdotd: Desired joint velocity vector.
    • JointVec const &qddotd: Desired joint acceleration vector.

3.5. H-Infinity Controller for Task Space Control

AbstractRobotXD::HinfController

This function computes the desired torque for task space control based on the desired task position, velocity, and acceleration, considering the robot's current state.

int HinfController(LieGroup::Vector3D const &grav, ExtendedPosition const &pd, ExtendedVelocity const &pdotd, ExtendedAcceleration const &pddotd)
  • Parameters
    • LieGroup::Vector3D const &grav: Gravity force direction.
    • ExtendedPosition const &pd: Desired task position vector.
    • ExtendedVelocity const &pdotd: Desired task velocity vector.
    • ExtendedAcceleration const &pddotd: Desired task acceleration vector.

4. Task Space Control APIs using a Forward Dynamics Approach

Neuromeka provides a built-in, special task space control that is kinematic singularity-free, based on the forward dynamics control (FDC) framework for IndySDK users. Combining forward dynamic robot simulation with impedance controller concepts, the FDC framework enhances pose tracking accuracy and stability near singularities by integrating high-gain PD control and a robust internal-loop compensator structure.

For further details, refer to the following research paper.

4.1. Forward Dynamics Controller

AbstractRobotXD::ForwardDynController

This function computes the desired joint torque to follow desired task trajectories, considering the dynamics of the robot. It uses the robot's nominal model to compute desired joint torque.

void ForwardDynController(AbstractRobot &robotNom, JointMat &Mn, JointMat &Cn, JointVec &Gn, ExtendedPosition const &posDes, ExtendedVelocity const &velDes, LieGroup::Vector3D const &gravDir)
  • Parameters
    • AbstractRobot &robotNom: Nominal robot model.
    • JointMat &Mn: Inertia matrix.
    • JointMat &Cn: Coriolis and centrifugal matrix.
    • JointVec &Gn: Gravity vector.
    • ExtendedPosition const &posDes: Desired task position vector.
    • ExtendedVelocity const &velDes: Desired task velocity vector.
    • LieGroup::Vector3D const &gravDir: Direction of gravity force.

4.2. Set Forward Dynamics Control Gains

AbstractRobotXD::setForwardDynControlGain

This function defines the gain parameters for forward dynamics control, including virtual mass and stiffness for translation and rotation.

void setForwardDynControlGain(JointVec const &kp, JointVec const &kv, JointVec const &ki, double const massxyz, double const massuvw, double const stiffnessxyz, double const stiffnessuvw)
  • Parameters
    • JointVec const &kp: Proportional gain vector.
    • JointVec const &kv: Damping gain vector.
    • JointVec const &ki: Integral gain vector.
    • double const massxyz: Virtual mass for translational movements.
    • double const massuvw: Virtual mass for rotational movements.
    • double const stiffnessxyz: Virtual stiffness for translational movements.
    • double const stiffnessuvw: Virtual stiffness for rotational movements.

4.3. Initialize Forward Dynamics Controller

AbstractRobotXD::initForwardDynController

This function initializes the forward dynamics controller by setting the control period, preparing the system for dynamic operation based on a specified time step.

void initForwardDynController(double delt)
  • Parameters
    • double delt: Control period.

4.4. Reset Forward Dynamics Controller

AbstractRobotXD::resetForwardDynController

This function resets the state of the forward dynamics controller and resets integral errors.

void resetForwardDynController()
  • Parameters
  • None

4.5 robot.computeTaskErr() Function

The robot.computeTaskErr() function is used to compute task frame errors in a robotic system. This function calculates the rotation and position errors between the actual and desired states of the robot.

  • Rotation Error (err_rot) - Measured in radians.
  • Position Error (err_pos) - Measured in meters.

Rotation Error Calculation

The rotation error is computed as follows:

  • Rtilde = R.icascade(Rd); // Compute the cascaded rotation matrix
  • err_rot = Rtilde.expCoord(); // Extract the exponential coordinates

Position Error Calculation

The position error is calculated as:

  • err_pos = desired_position – actual_position;
    • Here, desired_position and actual_position are vectors representing the target and current positions, respectively.

5. Admittance Control APIs

Neuromeka provides a built-in function to update desired task trajectories based on external forces for compliance control purposes. The controller ensures compliance during external contact through the force/torque sensor attached to the robot's end-effector. Neuromeka's IndySDK includes this specialized built-in function for adjusting desired task trajectories in response to external forces to enable compliance control. This allows the controller to adaptively respond to external contacts, utilizing the force/torque sensor on the end-effector for compliant behavior.

5.1. Reset Admittance Trajectory

AbstractRobotXD::resetAdmittanceTraj

This function resets the proxy trajectories and sets the proxy position trajectory to the current TCP (Tool Center Point) pose of the robot. It also sets the control period as a time step for simulating the nominal robot.

virtual void resetAdmittanceTraj(double delT)
  • Parameters
    • double delT: Control period.

5.2. Update Admittance Trajectory

AbstractRobotXD::updateAdmittanceTraj

This function updates the desired TCP trajectories based on the applied external force and sets these trajectories as proxy trajectories. It allows for selective compliance in either translation, rotation, or both, depending on the mode specified.

virtual void updateAdmittanceTraj(const Vector &posDes, const Vector &velDes, const Vector &accDes, Vector &tposProxy, Vector &tvelProxy, Vector &taccProxy, const Vector &f_ext, const Vector &f_ext_filtered, int mode)
  • Parameters
    • const Vector &posDes: Desired task position vector.
    • const Vector &velDes: Desired task velocity vector.
    • const Vector &accDes: Desired task acceleration vector.
    • Vector &tposProxy: Proxy task position vector.
    • Vector &tvelProxy: Proxy task velocity vector.
    • Vector &taccProxy: Proxy task acceleration vector.
    • const Vector &f_ext: External force.
    • const Vector &f_ext_filtered: Filtered external force.
    • int mode: Mode to select compliance direction (translation/rotation).
      • mode = 0: No update to the TCP trajectories (pure position control).
      • mode = 1: Only the displacement component will be compliant. The rotation component is pure position control.
      • mode = 2: Only the rotation component will be compliant. The displacement component is pure position control.
      • mode = any other number: Both displacement and rotational components will be compliant.

6. Coordinate and Property Setting APIs

This section introduces APIs dedicated to configuring coordinates and properties, crucial for accurately defining the spatial relationships and attributes of robotic components. It covers setting target coordinates, reference coordinates, F/T sensor coordinates, and tool properties.

6.1. Target Coordinate Setting

AbstractRobotXD::setTtarget

This function sets the HTransform matrix defining the transformation from the last joint to the TCP (Tool Center Point).

void setTtarget(LieGroup::Rotation const &R, LieGroup::Displacement const &r)
  • Parameters
    • LieGroup::Rotation const &R: Rotation matrix from the last joint to TCP.
    • LieGroup::Displacement const &r: Displacement vector from the last joint to TCP.

6.2. Reference Coordinate Setting

AbstractRobotXD::setTReference

This function sets the HTransform matrix from the global origin to the robot's base origin.

void setTReference(LieGroup::Rotation const &R, LieGroup::Displacement const &r)
  • Parameters
    • LieGroup::Rotation const &R: Rotation matrix from the global origin to the robot's origin.
    • LieGroup::Displacement const &r: Displacement vector from the global origin to the robot's origin.

6.3. F/T Sensor Coordinate Setting

AbstractRobotXD::setTFTSensor

This function sets the HTransform matrix from the TCP to the frame of the F/T (Force/Torque) sensor.

void setTFTSensor(LieGroup::Rotation const &R, LieGroup::Displacement const &r)
  • Parameters
    • LieGroup::Rotation const &R: Rotation matrix from TCP to F/T sensor frame.
    • LieGroup::Displacement const &r: Displacement vector from TCP to F/T sensor frame.

6.4. Tool Property Setting

AbstractRobotXD::toolWeight, toolXcom, toolYcom, toolZcom

These functions provides access to the tool's properties, such as weight and center of mass coordinates.

double const &toolWeight()
double &toolWeight()
double const &toolXcom()
double &toolXcom()
double const &toolYcom()
double &toolYcom()
double const &toolZcom()
double &toolZcom()