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.
-
uint8_t getMotorIDByIndex(const int index)
Gets the motor ID according to the passed index.
- Parameters:
index – Index of array
-
String getMotorControlMode()
Get the current operating mode of the motors.
- Returns:
The motor control mode.
-
void setMotorControlMode(const String &name)
Set the operating mode of the motors.
- Parameters:
name – Name of the mode (e.g. “position”, “current_position”, “velocity”).
-
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.
-
void setMotorNames(const char *const *names)
Set the unique names for motors (Must match the number of IDs)
- Parameters:
names – A list of “names” separated by comma.
-
String getMotorNameByID(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.
-
int getMotorCount()
Get the number of motors.
- Returns:
integer, number of motors.
-
bool isMotorFlipped(uint8_t id)
-
void beginCalibration(bool enableTimedCalibration, int duration)
Start the calibration process for the exoskeleton.
- Parameters:
enableTimedCalibration – If true, enables timed calibration mode.
duration – Duration in seconds for timed calibration.
-
void updateCalibration()
Update the calibration state, checking if the calibration is complete.
-
bool isExoCalibrating()
Check if the exoskeleton is currently calibrating.
- Returns:
True if in calibration mode, false otherwise.
-
void setModeSwitchButton(int pin)
Assign pin for mode switch interrupt.
- Parameters:
pin – Interrupt pin.
-
void setExoOperatingMode(const String &name)
Define the operating mode for exo.
- Parameters:
name – Operating mode (“GESTURE_FIXED”, “GESTURE_CONTINUOUS”, “FREE”)
-
String getExoOperatingMode()
Get the current operating mode for exo.
- Returns:
The current operating mode as a string.
-
ExoOperatingMode getExoOperatingModeEnum()
Get the current operating mode as an enum.
- Returns:
The current operating mode as an ExoOperatingMode enum.
-
bool checkModeSwitchButtonPressed()
Check if the mode switch button was pressed.
-
void update()
Update the exo state, including checking for button pressed, mode switching, and internal routines.
-
void cycleExoOperatingMode()
Cycle through the exo operating modes.
-
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.
-
bool getTorqueEnabledStatus(uint8_t id)
Check if torque is enabled for a motor.
- Parameters:
id – Motor ID.
-
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.
-
int16_t getCurrentLimit(uint8_t id)
Get the current limit in mA for a motor.
- Parameters:
id – Motor ID.
- Returns:
Current limit in milliamps.
-
void setCurrentLimit(uint8_t id, uint16_t current_mA)
Set the current limit for a motor.
- Parameters:
id – Motor ID.
current_mA – Current limit in milliamps.
-
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.
-
void setMotorControlMode(uint8_t id, const String &mode)
Set the current control mode of a motor.
- Parameters:
id – Motor ID.
mode – Control mode as a string (e.g. “POSITION”, “CURRENT_POSITION”, “VELOCITY”).
-
String getMotorControlMode(uint8_t id)
Get the current control mode of a motor.
- Parameters:
id – Motor ID.
- Returns:
Control mode as a string.
-
void setMotorMode(const String &mode)
Set the control mode for all motors.
- Parameters:
mode – Control mode as a string (e.g. “POSITION”, “CURRENT_POSITION”, “VELOCITY”).
-
String getMotorMode()
Get the current control mode of all motors.
- Returns:
Control mode as a string.
Public Static Attributes
-
static constexpr const char *VERSION = "0.2.12"
Current software version.
Private Members
-
Dynamixel2Arduino dxl_
Dynamixel2Arduino object for motor communication.
-
const uint8_t *motorIds_
Pointer to array of motor IDs.
-
const char *const *motorNames_
Pointer to array of motor names.
-
uint8_t numMotors_ = 0
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.
-
int modeSwitchPin = -1
Mode switch pin.
-
bool lastButtonState = false
Last interrupt time for mode switch button.
-
int buttonState = HIGH
Current state of the mode switch button.
-
unsigned long lastDebounceTime = 0
Last debounce time for mode switch button.
-
const unsigned long debounceDelay = 50
Debounce delay for mode switch button.
-
String motorControlMode_
Operating mode of motors.
-
ExoOperatingMode exoMode_ = FREE
Operating mode of exo.
-
bool isCalibrating = false
brief Flag to indicate if the exoskeleton is currently calibrating.
-
bool calibrationTimedMode = false
-
unsigned long calibrationStartTime
Start time for calibration.
-
unsigned long calibrationDuration
Duration for calibration in milliseconds.
-
bool flipMotor_[6] = {false, false, false, true, false, true}
Private Static Attributes
-
static volatile bool modeSwitchFlag
Mode switch flag for interrupt callback.
-
NMLHandExo(const uint8_t *ids, uint8_t numMotors, const float jointLimits[][2], const float *homeState = nullptr)