C++ API Reference

This section describes the C++ API of the NML Hand Exoskeleton.

class NMLHandExo

Class to manage the NML Hand Exoskeleton, providing initialization, motor control, and telemetry.

Public Functions

NMLHandExo(const uint8_t *ids, uint8_t numMotors, const float jointLimits[][2], const float *homeState = nullptr)

Constructor.

Parameters:
  • ids – Pointer to array of motor IDs.

  • numMotors – Number of motors in the device.

  • jointLimits – Pointer to 2D array defining [min, max] joint limits in degrees.

  • homeState – Optional array of home positions (in degrees). Defaults to zero offsets.

inline ~NMLHandExo()

Destructor.

void initializeSerial(int baud)

Initialize the serial port for Dynamixel communication.

Parameters:

baud – Baud rate to initialize.

void initializeMotors()

Initialize all motors: disables torque, sets position mode, then re-enables torque.

int getMotorID(const String &token)

Get the motor ID from a user-supplied token (either name or ID as a string).

Parameters:

token – The token string (e.g. “WRIST” or “1”).

Returns:

The motor ID or -1 if not found.

int getIndexById(uint8_t id)

Get the index of a motor in the internal arrays from its ID.

Parameters:

id – The motor ID.

Returns:

The index in the motor array or -1 if not found.

int getMotorIDByName(const String &name)

Get the motor ID by name.

Parameters:

name – Name of the motor (e.g. “WRIST”).

Returns:

The motor ID or -1 if not found.

String getNameByMotorID(uint8_t id)

Get the motor name from its ID.

Parameters:

id – The motor ID.

Returns:

The name of the motor.

int angleToTicks(float angle_deg, int index)

Convert a relative angle (degrees) to Dynamixel tick counts.

Parameters:
  • angle_deg – Angle in degrees.

  • index – Index of the motor.

Returns:

Ticks equivalent to the angle.

void setZeroOffset(uint8_t id)

Calibrate the zero offset for a motor by reading its current position.

Parameters:

id – Motor ID.

float getZeroOffset(uint8_t id)

Get the stored zero offset for a motor.

Parameters:

id – Motor ID.

Returns:

Zero offset in degrees.

void resetAllZeros()

Reset zero offsets for all motors using their current positions.

String getDeviceInfo()

Get a string summarizing the device information.

Returns:

Information string.

float getRelativeAngle(uint8_t id)

Get the relative angle (degrees) of a motor.

Parameters:

id – Motor ID.

Returns:

Relative angle in degrees.

void setRelativeAngle(uint8_t id, float angleDeg)

Command the motor to a relative angle.

Parameters:
  • id – Motor ID.

  • angleDeg – Relative angle in degrees.

float getAbsoluteAngle(uint8_t id)

Get the absolute angle (degrees) of a motor.

Parameters:

id – Motor ID.

Returns:

Absolute angle in degrees.

void setAbsoluteAngle(uint8_t id, float angleDeg)

Command the motor to an absolute angle.

Parameters:
  • id – Motor ID.

  • angleDeg – Absolute angle in degrees.

float getZeroAngle(uint8_t id)

Get the stored zero angle of a motor.

Parameters:

id – Motor ID.

Returns:

Zero angle in degrees.

void setHome(uint8_t id)

Home the motor to its stored zero position.

Parameters:

id – Motor ID.

void homeAllMotors()

Home all motors to their stored zero positions.

void setAngleById(uint8_t id, float angleDeg)

Command the motor to an angle by ID.

Parameters:
  • id – Motor ID.

  • angleDeg – Angle in degrees.

void setAngleByAlias(const String &alias, float angleDeg)

Command a motor using an alias (name) and angle.

Parameters:
  • alias – Motor name (e.g. “WRIST”).

  • angleDeg – Angle in degrees.

void setMotorLowerBound(uint8_t id, float lowerBound)

Set the lower joint limit (in degrees) for a motor.

Parameters:
  • id – Motor ID.

  • lowerBound – New lower bound in degrees.

void setMotorUpperBound(uint8_t id, float upperBound)

Set the upper joint limit (in degrees) for a motor.

Parameters:
  • id – Motor ID.

  • upperBound – New upper bound in degrees.

String getMotorLimits(uint8_t id)

Get the joint angle limits for a motor.

Parameters:

id – Motor ID.

Returns:

A string in the format “[min, max]” or error message.

void setMotorLimits(uint8_t id, float lowerLimit, float upperLimit)

Set the joint angle limits for a motor.

Parameters:
  • id – Motor ID.

  • lowerLimit – New lower limit in degrees.

  • upperLimit – New upper limit in degrees.

void enableTorque(uint8_t id, bool enable)

Enable or disable torque for a motor.

Parameters:
  • id – Motor ID.

  • enable – True to enable torque, false to disable.

int16_t getCurrent(uint8_t id)

Get the current draw from a motor.

Parameters:

id – Motor ID.

Returns:

Raw current value.

void setCurrentLimit(uint8_t id, uint16_t current_mA)
void setTorque(uint8_t id, float torque_Nm)

Set the calculated torque in N·m for a motor.

Parameters:

id – Motor ID.

Returns:

Torque in Newton-meters.

float getTorque(uint8_t id)

Get the calculated torque in N·m for a motor.

Parameters:

id – Motor ID.

Returns:

Torque in Newton-meters.

void setVelocityLimit(uint8_t id, uint32_t vel)

Set the velocity limit of a motor.

Parameters:
  • id – Motor ID.

  • vel – Velocity limit.

uint32_t getVelocityLimit(uint8_t id)

Get the velocity limit of a motor.

Parameters:

id – Motor ID.

Returns:

Velocity limit.

void setAccelerationLimit(uint8_t id, uint32_t acc)

Set the acceleration limit of a motor.

Parameters:
  • id – Motor ID.

  • acc – Acceleration limit.

uint32_t getAccelerationLimit(uint8_t id)

Get the acceleration limit of a motor.

Parameters:

id – Motor ID.

Returns:

Acceleration limit.

void rebootMotor(uint8_t id)

Reboot a motor.

Parameters:

id – Motor ID.

void getMotorInfo(uint8_t id)

Ping a motor to verify communication.

Parameters:

id – Motor ID.

void setBaudRate(uint8_t id, uint32_t baudrate)

Set the baud rate of a motor.

Parameters:
  • id – Motor ID.

  • baudrate – New baud rate.

uint32_t getBaudRate(uint8_t id)

Get the baud rate of a motor.

Parameters:

id – Motor ID.

Returns:

Baud rate.

void setMotorLED(uint8_t id, bool state)

Set the LED state of a motor.

Parameters:
  • id – Motor ID.

  • state – True for on, false for off.

void setAllMotorLED(bool state)

Set the LED state of all motors.

Parameters:

state – True for on, false for off.

Public Static Attributes

static constexpr const char *VERSION = "1.2.3"

Current software version.

Private Members

Dynamixel2Arduino dxl_

Dynamixel2Arduino object for motor communication.

const uint8_t *ids_

Pointer to array of motor IDs.

uint8_t numMotors_

Number of motors configured.

float (*jointLimits_)[2]

Pointer to 2D array of joint limits [min, max] for each motor.

float *zeroOffsets_

Array of zero offsets for each motor.

uint16_t *currentLimits_

Array of current limits for each motor.