Class TrossenArmDriver

Class Documentation

class TrossenArmDriver

Trossen Arm Driver.

Public Functions

TrossenArmDriver()

Construct the Trossen Arm Driver object.

~TrossenArmDriver()

Destroy the Trossen Arm Driver object.

void configure(Model model, EndEffector end_effector, const std::string serv_ip, bool clear_error, double timeout = 20.0)

Configure the driver.

Parameters:
  • model – Model of the robot

  • end_effector – End effector properties

  • serv_ip – IP address of the robot

  • clear_error – Whether to clear the error state of the robot

  • timeout – Timeout for connection to the arm controller’s TCP server in seconds, default is 20.0s

void cleanup(bool reboot_controller = false)

Cleanup the driver.

Parameters:

reboot_controller – Whether to reboot the controller

inline void reboot_controller()

Reboot the controller and cleanup the driver.

Note

This function is a wrapper for cleanup(true)

void clear_error()

Clear the error state of the robot.

Note

This function calls cleanup() with reboot_controller = false and configure() with clear_error = true internally

void set_all_positions(const std::vector<double> &goal_positions, double goal_time = 2.0, bool blocking = true, const std::optional<std::vector<double>> &goal_feedforward_velocities = std::nullopt, const std::optional<std::vector<double>> &goal_feedforward_accelerations = std::nullopt)

Set the positions of all joints.

  • if longer than 0.2s, quintic polynomial interpolation is used with goal derivatives defaulted to zero if not specified

  • else if longer than 0.001s, linear interpolation is used

  • else, no interpolation is used and the goal values are applied immediately

Note

The size of the vectors should be equal to the number of joints

Note

To avoid numerical issues, interpolation type used is determined automatically based on goal_time:

Parameters:
  • goal_positions – Positions in rad for arm joints and m for the gripper joint

  • goal_time – Optional: goal time in s when the goal positions should be reached, default 2.0s

  • blocking – Optional: whether to block until the goal positions are reached, default true

  • goal_feedforward_velocities – Optional: feedforward velocities in rad/s for arm joints and m/s for the gripper joint

  • goal_feedforward_accelerations – Optional: feedforward accelerations in rad/s^2 for arm joints and m/s^2 for the gripper joint

void set_arm_positions(const std::vector<double> &goal_positions, double goal_time = 2.0, bool blocking = true, const std::optional<std::vector<double>> &goal_feedforward_velocities = std::nullopt, const std::optional<std::vector<double>> &goal_feedforward_accelerations = std::nullopt)

Set the positions of the arm joints.

  • if longer than 0.2s, quintic polynomial interpolation is used with goal derivatives defaulted to zero if not specified

  • else if longer than 0.001s, linear interpolation is used

  • else, no interpolation is used and the goal values are applied immediately

Note

The size of the vectors should be equal to the number of arm joints

Note

To avoid numerical issues, interpolation type used is determined automatically based on goal_time:

Parameters:
  • goal_positions – Positions in rad

  • goal_time – Optional: goal time in s when the goal positions should be reached, default 2.0s

  • blocking – Optional: whether to block until the goal positions are reached, default true

  • goal_feedforward_velocities – Optional: feedforward velocities in rad/s

  • goal_feedforward_accelerations – Optional: feedforward accelerations in rad/s^2

void set_gripper_position(double goal_position, double goal_time = 2.0, bool blocking = true, std::optional<double> goal_feedforward_velocity = std::nullopt, std::optional<double> goal_feedforward_acceleration = std::nullopt)

Set the position of the gripper.

  • if longer than 0.2s, quintic polynomial interpolation is used with goal derivatives defaulted to zero if not specified

  • else if longer than 0.001s, linear interpolation is used

  • else, no interpolation is used and the goal values are applied immediately

Note

To avoid numerical issues, interpolation type used is determined automatically based on goal_time:

Parameters:
  • goal_position – Position in m

  • goal_time – Optional: goal time in s when the goal position should be reached, default 2.0s

  • blocking – Optional: whether to block until the goal position is reached, default true

  • goal_feedforward_velocity – Optional: feedforward velocity in m/s

  • goal_feedforward_acceleration – Optional: feedforward acceleration in m/s^2

void set_joint_position(uint8_t joint_index, double goal_position, double goal_time = 2.0, bool blocking = true, std::optional<double> goal_feedforward_velocity = std::nullopt, std::optional<double> goal_feedforward_acceleration = std::nullopt)

Set the position of a joint.

  • if longer than 0.2s, quintic polynomial interpolation is used with goal derivatives defaulted to zero if not specified

  • else if longer than 0.001s, linear interpolation is used

  • else, no interpolation is used and the goal values are applied immediately

Note

To avoid numerical issues, interpolation type used is determined automatically based on goal_time:

Parameters:
  • joint_index – The index of the joint in [0, num_joints - 1]

  • goal_position – Position in rad for arm joints and m for the gripper joint

  • goal_time – Optional: goal time in s when the goal position should be reached, default 2.0s

  • blocking – Optional: whether to block until the goal position is reached, default true

  • goal_feedforward_velocity – Optional: feedforward velocity in rad/s for arm joints and m/s for the gripper joint

  • goal_feedforward_acceleration – Optional: feedforward acceleration in rad/s^2 for arm joints and m/s^2 for the gripper joint

void set_cartesian_positions(const std::array<double, 6> &goal_positions, InterpolationSpace interpolation_space, double goal_time = 2.0, bool blocking = true, const std::optional<std::array<double, 6>> &goal_feedforward_velocities = std::nullopt, const std::optional<std::array<double, 6>> &goal_feedforward_accelerations = std::nullopt, int num_trajectory_check_samples = 0)

Set the position of the end effector in Cartesian space.

  • if longer than 0.2s, quintic polynomial interpolation is used with goal derivatives defaulted to zero if not specified

  • else if longer than 0.001s, linear interpolation is used

  • else, no interpolation is used and the goal values are applied immediately

Note

The first 3 elements of goal_positions are the translation and the last 3 elements are the angle-axis representation of the rotation

Note

The first 3 elements of goal_feedforward_velocities are the linear velocity and the last 3 elements are the angular velocity

Note

The first 3 elements of goal_feedforward_accelerations are the linear acceleration and the last 3 elements are the angular acceleration

Note

To avoid numerical issues, interpolation type used is determined automatically based on goal_time:

Parameters:
  • goal_positions – Spatial position of the end effector frame measured in the base frame in m and rad

  • interpolation_space – Interpolation space, one of InterpolationSpace::joint or InterpolationSpace::cartesian

  • goal_time – Optional: goal time in s when the goal positions should be reached, default 2.0s

  • blocking – Optional: whether to block until the goal positions are reached, default true

  • goal_feedforward_velocities – Optional: spatial velocity of the end effector frame with respect to the base frame measured in the base frame in m/s and rad/s

  • goal_feedforward_accelerations – Optional: spatial acceleration of the end effector frame with respect to the base frame measured in the base frame in m/s^2 and rad/s^2

  • num_trajectory_check_samples – Optional: number of evenly spaced sampled time steps to check trajectory feasibility, default 0

void set_all_velocities(const std::vector<double> &goal_velocities, double goal_time = 2.0, bool blocking = true, const std::optional<std::vector<double>> &goal_feedforward_accelerations = std::nullopt)

Set the velocities of all joints.

  • if longer than 0.2s, cubic polynomial interpolation is used with goal derivatives defaulted to zero if not specified

  • else if longer than 0.001s, linear interpolation is used

  • else, no interpolation is used and the goal values are applied immediately

Note

The size of the vectors should be equal to the number of joints

Note

To avoid numerical issues, interpolation type used is determined automatically based on goal_time:

Parameters:
  • goal_velocities – Velocities in rad/s for arm joints and m/s for the gripper joint

  • goal_time – Optional: goal time in s when the goal velocities should be reached, default 2.0s

  • blocking – Optional: whether to block until the goal velocities are reached, default true

  • goal_feedforward_accelerations – Optional: feedforward accelerations in rad/s^2 for arm joints and m/s^2 for the gripper joint

void set_arm_velocities(const std::vector<double> &goal_velocities, double goal_time = 2.0, bool blocking = true, const std::optional<std::vector<double>> &goal_feedforward_accelerations = std::nullopt)

Set the velocities of the arm joints.

  • if longer than 0.2s, cubic polynomial interpolation is used with goal derivatives defaulted to zero if not specified

  • else if longer than 0.001s, linear interpolation is used

  • else, no interpolation is used and the goal values are applied immediately

Note

The size of the vectors should be equal to the number of arm joints

Note

To avoid numerical issues, interpolation type used is determined automatically based on goal_time:

Parameters:
  • goal_velocities – Velocities in rad

  • blocking – Optional: whether to block until the goal velocities are reached, default true

  • goal_time – Optional: goal time in s when the goal velocities should be reached, default 2.0s

  • goal_feedforward_accelerations – Optional: feedforward accelerations in rad/s^2

void set_gripper_velocity(double goal_velocity, double goal_time = 2.0, bool blocking = true, std::optional<double> goal_feedforward_acceleration = std::nullopt)

Set the velocity of the gripper.

  • if longer than 0.2s, cubic polynomial interpolation is used with goal derivatives defaulted to zero if not specified

  • else if longer than 0.001s, linear interpolation is used

  • else, no interpolation is used and the goal values are applied immediately

Note

To avoid numerical issues, interpolation type used is determined automatically based on goal_time:

Parameters:
  • goal_velocity – Velocity in m/s

  • goal_time – Optional: goal time in s when the goal velocity should be reached, default 2.0s

  • blocking – Optional: whether to block until the goal velocity is reached, default true

  • goal_feedforward_acceleration – Optional: feedforward acceleration in m/s^2

void set_joint_velocity(uint8_t joint_index, double goal_velocity, double goal_time = 2.0, bool blocking = true, std::optional<double> goal_feedforward_acceleration = std::nullopt)

Set the velocity of a joint.

  • if longer than 0.2s, cubic polynomial interpolation is used with goal derivatives defaulted to zero if not specified

  • else if longer than 0.001s, linear interpolation is used

  • else, no interpolation is used and the goal values are applied immediately

Note

To avoid numerical issues, interpolation type used is determined automatically based on goal_time:

Parameters:
  • joint_index – The index of the joint in [0, num_joints - 1]

  • goal_velocity – Velocity in rad/s for arm joints and m/s for the gripper joint

  • goal_time – Optional: goal time in s when the goal velocity should be reached, default 2.0s

  • blocking – Optional: whether to block until the goal velocity is reached, default true

  • goal_feedforward_acceleration – Optional: feedforward acceleration in rad/s^2 for arm joints and m/s^2 for the gripper joint

void set_cartesian_velocities(const std::array<double, 6> &goal_velocities, InterpolationSpace interpolation_space, double goal_time = 2.0, bool blocking = true, const std::optional<std::array<double, 6>> &goal_feedforward_accelerations = std::nullopt)

Set the velocity of the end effector in Cartesian space.

  • if longer than 0.2s, cubic polynomial interpolation is used with goal derivatives defaulted to zero if not specified

  • else if longer than 0.001s, linear interpolation is used

  • else, no interpolation is used and the goal values are applied immediately

Note

The first 3 elements of goal_velocities are the linear velocity and the last 3 elements are the angular velocity

Note

The first 3 elements of goal_feedforward_accelerations are the linear acceleration and the last 3 elements are the angular acceleration

Note

To avoid numerical issues, interpolation type used is determined automatically based on goal_time:

Parameters:
  • goal_velocities – Spatial velocity of the end effector frame with respect to the base frame measured in the base frame in m/s and rad/s

  • interpolation_space – Interpolation space, one of InterpolationSpace::joint or InterpolationSpace::cartesian

  • goal_time – Optional: goal time in s when the goal velocities should be reached, default 2.0s

  • blocking – Optional: whether to block until the goal velocities are reached, default true

  • goal_feedforward_accelerations – Optional: spatial acceleration of the end effector frame with respect to the base frame measured in the base frame in m/s^2 and rad/s^2

void set_all_external_efforts(const std::vector<double> &goal_external_efforts, double goal_time = 2.0, bool blocking = true)

Set the external efforts of all joints.

  • if longer than 0.001s, linear interpolation is used

  • else, no interpolation is used and the goal values are applied immediately

Note

The size of the vectors should be equal to the number of joints

Note

To avoid numerical issues, interpolation type used is determined automatically based on goal_time:

Parameters:
  • goal_external_efforts – External efforts in Nm for arm joints and N for the gripper joint

  • goal_time – Optional: goal time in s when the goal external efforts should be reached, default 2.0s

  • blocking – Optional: whether to block until the goal external efforts are reached, default true

void set_arm_external_efforts(const std::vector<double> &goal_external_efforts, double goal_time = 2.0, bool blocking = true)

Set the external efforts of the arm joints.

  • if longer than 0.001s, linear interpolation is used

  • else, no interpolation is used and the goal values are applied immediately

Note

The size of the vectors should be equal to the number of arm joints

Note

To avoid numerical issues, interpolation type used is determined automatically based on goal_time:

Parameters:
  • goal_external_efforts – External efforts in Nm

  • goal_time – Optional: goal time in s when the goal external efforts should be reached, default 2.0s

  • blocking – Optional: whether to block until the goal external efforts are reached, default true

void set_gripper_external_effort(double goal_external_effort, double goal_time = 2.0, bool blocking = true)

Set the external effort of the gripper.

  • if longer than 0.001s, linear interpolation is used

  • else, no interpolation is used and the goal values are applied immediately

Note

To avoid numerical issues, interpolation type used is determined automatically based on goal_time:

Parameters:
  • goal_external_effort – External effort in N

  • goal_time – Optional: goal time in s when the goal external effort should be reached, default 2.0s

  • blocking – Optional: whether to block until the goal external effort is reached, default true

void set_joint_external_effort(uint8_t joint_index, double goal_external_effort, double goal_time = 2.0, bool blocking = true)

Set the external effort of a joint.

  • if longer than 0.001s, linear interpolation is used

  • else, no interpolation is used and the goal values are applied immediately

Note

To avoid numerical issues, interpolation type used is determined automatically based on goal_time:

Parameters:
  • joint_index – The index of the joint in [0, num_joints - 1]

  • goal_external_effort – External effort in Nm for arm joints and N for the gripper joint

  • goal_time – Optional: goal time in s when the goal external effort should be reached, default 2.0s

  • blocking – Optional: whether to block until the goal external effort is reached, default true

void set_cartesian_external_efforts(const std::array<double, 6> &goal_external_efforts, InterpolationSpace interpolation_space, double goal_time = 2.0, bool blocking = true)

Set the external efforts of the end effector in Cartesian space.

  • if longer than 0.001s, linear interpolation is used

  • else, no interpolation is used and the goal values are applied immediately

Note

The first 3 elements of goal_external_efforts are the force and the last 3 elements are the torque

Note

To avoid numerical issues, interpolation type used is determined automatically based on goal_time:

Parameters:
  • goal_external_efforts – Spatial external efforts applied to the end effector frame measured in the base frame in N and Nm

  • interpolation_space – Interpolation space, one of InterpolationSpace::joint or InterpolationSpace::cartesian

  • goal_time – Optional: goal time in s when the goal external efforts should be reached, default 2.0s

  • blocking – Optional: whether to block until the goal external efforts are reached, default true

void set_all_efforts(const std::vector<double> &goal_efforts, double goal_time = 2.0, bool blocking = true)

Set the efforts of all joints.

  • if longer than 0.001s, linear interpolation is used

  • else, no interpolation is used and the goal values are applied immediately

Note

The size of the vectors should be equal to the number of joints

Note

To avoid numerical issues, interpolation type used is determined automatically based on goal_time:

Parameters:
  • goal_efforts – Efforts in Nm for arm joints and N for the gripper joint

  • goal_time – Optional: goal time in s when the goal efforts should be reached, default 2.0s

  • blocking – Optional: whether to block until the goal efforts are reached, default true

void set_arm_efforts(const std::vector<double> &goal_efforts, double goal_time = 2.0, bool blocking = true)

Set the efforts of the arm joints.

  • if longer than 0.001s, linear interpolation is used

  • else, no interpolation is used and the goal values are applied immediately

Note

The size of the vectors should be equal to the number of arm joints

Note

To avoid numerical issues, interpolation type used is determined automatically based on goal_time:

Parameters:
  • goal_efforts – Efforts in Nm

  • goal_time – Optional: goal time in s when the goal efforts should be reached, default 2.0s

  • blocking – Optional: whether to block until the goal efforts are reached, default true

void set_gripper_effort(double goal_effort, double goal_time = 2.0, bool blocking = true)

Set the effort of the gripper.

  • if longer than 0.001s, linear interpolation is used

  • else, no interpolation is used and the goal values are applied immediately

Note

To avoid numerical issues, interpolation type used is determined automatically based on goal_time:

Parameters:
  • goal_effort – Effort in N

  • goal_time – Optional: goal time in s when the goal effort should be reached, default 2.0s

  • blocking – Optional: whether to block until the goal effort is reached, default true

void set_joint_effort(uint8_t joint_index, double goal_effort, double goal_time = 2.0, bool blocking = true)

Set the effort of a joint.

  • if longer than 0.001s, linear interpolation is used

  • else, no interpolation is used and the goal values are applied immediately

Note

To avoid numerical issues, interpolation type used is determined automatically based on goal_time:

Parameters:
  • joint_index – The index of the joint in [0, num_joints - 1]

  • goal_effort – Effort in Nm for arm joints and N for the gripper joint

  • goal_time – Optional: goal time in s when the goal effort should be reached, default 2.0s

  • blocking – Optional: whether to block until the goal effort is reached, default true

void load_configs_from_file(const std::string &file_path)

Load configurations from a YAML file and set them.

Parameters:

file_path – The file path to load the configurations

void set_factory_reset_flag(bool flag = true)

Set the factory reset flag.

Parameters:

flag – Whether to reset the configurations to factory defaults at the next startup

void set_ip_method(IPMethod method = IPMethod::manual)

Set the IP method.

Parameters:

method – The IP method to set, one of IPMethod::manual or IPMethod::dhcp

void set_manual_ip(const std::string manual_ip = "192.168.1.2")

Set the manual IP.

Parameters:

manual_ip – The manual IP address to set

void set_dns(const std::string dns = "8.8.8.8")

Set the DNS.

Parameters:

dns – The DNS to set

void set_gateway(const std::string gateway = "192.168.1.1")

Set the gateway.

Parameters:

gateway – The gateway to set

void set_subnet(const std::string subnet = "255.255.255.0")

Set the subnet.

Parameters:

subnet – The subnet to set

void set_joint_characteristics(const std::vector<JointCharacteristic> &joint_characteristics)

Set the joint characteristics.

  • effort_correction: [0.2, 5.0]

  • friction_transition_velocity: positive

Note

The size of the vector should be equal to the number of joints

Note

Some joint characteristics are required to be within the following ranges

Parameters:

joint_characteristics – Joint characteristics

void set_effort_corrections(const std::vector<double> &effort_corrections)

Set the effort corrections.

Note

This configuration is used to map the efforts in Nm or N to the motor effort unit, i.e., effort_correction = motor effort unit / Nm or N

Note

The size of the vector should be equal to the number of joints

Note

Each element in the vector should be within the range [0.2, 5.0]

Parameters:

effort_corrections – Effort corrections in motor effort unit / Nm or N

void set_friction_transition_velocities(const std::vector<double> &friction_transition_velocities)

Set the friction transition velocities.

Note

The size of the vector should be equal to the number of joints

Note

Each element in the vector should be positive

Parameters:

friction_transition_velocities – Friction transition velocities in rad/s for arm joints and m/s for the gripper joint

void set_friction_constant_terms(const std::vector<double> &friction_constant_terms)

Set the friction constant terms.

Note

The size of the vector should be equal to the number of joints

Parameters:

friction_constant_terms – Friction constant terms in Nm for arm joints and N for the gripper joint

void set_friction_coulomb_coefs(const std::vector<double> &friction_coulomb_coefs)

Set the friction coulomb coefs.

Note

The size of the vector should be equal to the number of joints

Parameters:

friction_coulomb_coefs – Friction coulomb coefs in Nm/Nm for arm joints and N/N for the gripper joint

void set_friction_viscous_coefs(const std::vector<double> &friction_viscous_coefs)

Set the friction viscous coefs.

Note

The size of the vector should be equal to the number of joints

Parameters:

friction_viscous_coefs – Friction viscous coefs in Nm/(rad/s) for arm joints and N/(m/s) for the gripper joint

void set_position_offsets(const std::vector<double> &position_offsets)

Set the position offsets.

Note

The size of the vector should be equal to the number of joints

Parameters:

position_offsets – Position offsets in rad for arm joints and m for the gripper joint

void set_joint_modes(const std::vector<Mode> &modes)

Set the modes of each joint.

  • Mode::idle

  • Mode::position

  • Mode::velocity

  • Mode::external_effort

  • Mode::effort

Note

The size of the vector should be equal to the number of joints

Parameters:

modes – Desired modes for each joint, one of

void set_all_modes(Mode mode = Mode::idle)

Set all joints to the same mode.

  • Mode::idle

  • Mode::position

  • Mode::velocity

  • Mode::external_effort

  • Mode::effort

Parameters:

mode – Desired mode for all joints, one of

void set_arm_modes(Mode mode = Mode::idle)

Set the mode of the arm joints.

  • Mode::idle

  • Mode::position

  • Mode::velocity

  • Mode::external_effort

  • Mode::effort

Warning

This method does not change the gripper joint’s mode

Parameters:

mode – Desired mode for the arm joints, one of

void set_gripper_mode(Mode mode = Mode::idle)

Set the mode of the gripper joint.

  • Mode::idle

  • Mode::position

  • Mode::velocity

  • Mode::external_effort

  • Mode::effort

Warning

This method does not change the arm joints’ mode

Parameters:

mode – Desired mode for the gripper joint, one of

void set_end_effector(const EndEffector &end_effector)

Set the end effector properties.

Parameters:

end_effector – The end effector properties

void set_joint_limits(const std::vector<JointLimit> &joint_limits)

Set the joint limits.

Parameters:

joint_limits – Joint limits of all joints

void set_motor_parameters(const std::vector<std::map<Mode, MotorParameter>> &motor_parameters)

Set the motor parameters.

Parameters:

motor_parameters – Motor parameters of all modes of all joints

void set_algorithm_parameter(const AlgorithmParameter &algorithm_parameter)

Set the algorithm parameter.

Parameters:

algorithm_parameter – Parameter used for robotic algorithms

uint8_t get_num_joints() const

Get the number of joints.

Returns:

Number of joints

std::string get_driver_version() const

Get driver version.

Returns:

Driver version

std::string get_controller_version() const

Get controller firmware version.

Returns:

Controller firmware version

RobotOutput get_robot_output()

Get the robot output.

Returns:

Robot output

std::vector<double> get_all_positions()

Get the positions of all joints.

Returns:

Positions in rad for arm joints and m for the gripper joint

std::vector<double> get_arm_positions()

Get the positions of the arm joints.

Returns:

Positions in rad

double get_gripper_position()

Get the position of the gripper.

Returns:

Position in m

double get_joint_position(uint8_t joint_index)

Get the position of a joint.

Parameters:

joint_index – The index of the joint in [0, num_joints - 1]

Returns:

Position in rad for arm joints and m for the gripper joint

std::array<double, 6> get_cartesian_positions()

Get the Cartesian positions.

Note

The first 3 elements are the translation and the last 3 elements are the angle-axis representation of the rotation

Returns:

Spatial position of the end effector frame measured in the base frame in m and rad

std::vector<double> get_all_velocities()

Get the velocities of all joints.

Returns:

Velocities in rad/s for arm joints and m/s for the gripper joint

std::vector<double> get_arm_velocities()

Get the velocities of the arm joints.

Returns:

Velocities in rad/s

double get_gripper_velocity()

Get the velocity of the gripper.

Returns:

Velocity in m/s

double get_joint_velocity(uint8_t joint_index)

Get the velocity of a joint.

Parameters:

joint_index – The index of the joint in [0, num_joints - 1]

Returns:

Velocity in rad/s for arm joints and m/s for the gripper joint

std::array<double, 6> get_cartesian_velocities()

Get the Cartesian velocities.

Note

The first 3 elements are the linear velocity and the last 3 elements are the angular velocity

Returns:

Spatial velocity of the end effector frame with respect to the base frame measured in the base frame in m/s and rad/s

std::vector<double> get_all_accelerations()

Get the accelerations.

Returns:

Accelerations in rad/s^2 for arm joints and m/s^2 for the gripper joint

std::vector<double> get_arm_accelerations()

Get the accelerations of all joints.

Returns:

Accelerations in rad/s^2 for arm joints and m/s^2 for the gripper joint

double get_gripper_acceleration()

Get the acceleration of the gripper.

Returns:

Acceleration in m/s^2

double get_joint_acceleration(uint8_t joint_index)

Get the acceleration of a joint.

Parameters:

joint_index – The index of the joint in [0, num_joints - 1]

Returns:

Acceleration in rad/s^2 for arm joints and m/s^2 for the gripper joint

std::array<double, 6> get_cartesian_accelerations()

Get the Cartesian accelerations.

Note

The first 3 elements are the linear acceleration and the last 3 elements are the angular acceleration

Returns:

Spatial acceleration of the end effector frame with respect to the base frame measured in the base frame in m/s^2 and rad/s^2

std::vector<double> get_all_efforts()

Get the efforts of all joints.

Returns:

Efforts in Nm for arm joints and N for the gripper joint

std::vector<double> get_arm_efforts()

Get the efforts of the arm joints.

Returns:

Efforts in Nm

double get_gripper_effort()

Get the effort of the gripper.

Returns:

Effort in N

double get_joint_effort(uint8_t joint_index)

Get the effort of a joint.

Parameters:

joint_index – The index of the joint in [0, num_joints - 1]

Returns:

Effort in Nm for arm joints and N for the gripper joint

std::vector<double> get_all_external_efforts()

Get the external efforts of all joints.

Returns:

External efforts in Nm for arm joints and N for the gripper joint

std::vector<double> get_arm_external_efforts()

Get the external efforts of the arm joints.

Returns:

External efforts in Nm

double get_gripper_external_effort()

Get the external effort of the gripper.

Returns:

External effort in N

double get_joint_external_effort(uint8_t joint_index)

Get the external effort of a joint.

Parameters:

joint_index – The index of the joint in [0, num_joints - 1]

Returns:

External effort in Nm for arm joints and N for the gripper joint

std::array<double, 6> get_cartesian_external_efforts()

Get the compensation efforts.

Note

The first 3 elements are the force and the last 3 elements are the torque

Returns:

Spatial external efforts applied to the end effector frame measured in the base frame in N and Nm

std::vector<double> get_all_compensation_efforts()

Get the compensation efforts of all joints.

Returns:

Compensation efforts in Nm for arm joints and N for the gripper joint

std::vector<double> get_arm_compensation_efforts()

Get the compensation efforts of the arm joints.

Returns:

Compensation efforts in Nm

double get_gripper_compensation_effort()

Get the compensation effort of the gripper.

Returns:

Compensation effort in N

double get_joint_compensation_effort(uint8_t joint_index)

Get the compensation effort of a joint.

Parameters:

joint_index – The index of the joint in [0, num_joints - 1]

Returns:

Compensation effort in Nm for arm joints and N for the gripper joint

std::vector<double> get_all_rotor_temperatures()

Get the rotor temperatures of all joints.

Returns:

Rotor temperatures in C

std::vector<double> get_arm_rotor_temperatures()

Get the rotor temperatures of the arm joints.

Returns:

Rotor temperatures in C

double get_gripper_rotor_temperature()

Get the rotor temperature of the gripper.

Returns:

Rotor temperature in C

double get_joint_rotor_temperature(uint8_t joint_index)

Get the rotor temperature of a joint.

Parameters:

joint_index – The index of the joint in [0, num_joints - 1]

Returns:

Rotor temperature in C

std::vector<double> get_all_driver_temperatures()

Get the driver temperatures of all joints.

Returns:

Driver temperatures in C

std::vector<double> get_arm_driver_temperatures()

Get the driver temperatures of the arm joints.

Returns:

Driver temperatures in C

double get_gripper_driver_temperature()

Get the driver temperature of the gripper.

Returns:

Driver temperature in C

double get_joint_driver_temperature(uint8_t joint_index)

Get the driver temperature of a joint.

Parameters:

joint_index – The index of the joint in [0, num_joints - 1]

Returns:

Driver temperature in C

void save_configs_to_file(const std::string &file_path)

Save configurations to a YAML file.

Parameters:

file_path – The file path to store the configurations

bool get_factory_reset_flag()

Get the factory reset flag.

Returns:

true The configurations will be reset to factory defaults at the next startup

Returns:

false The configurations will not be reset to factory defaults at the next startup

IPMethod get_ip_method()

Get the IP method.

Returns:

The IP method of the robot

std::string get_manual_ip()

Get the manual IP.

Returns:

Manual IP address

std::string get_dns()

Get the DNS.

Returns:

DNS address

std::string get_gateway()

Get the gateway.

Returns:

Gateway address

std::string get_subnet()

Get the subnet.

Returns:

Subnet address

std::vector<JointCharacteristic> get_joint_characteristics()

Get the joint characteristics.

Returns:

Joint characteristics

std::vector<double> get_effort_corrections()

Get the effort corrections.

Returns:

Effort corrections in motor effort unit / Nm or N

std::vector<double> get_friction_transition_velocities()

Get the friction transition velocities.

Returns:

Friction transition velocities in rad/s for arm joints and m/s for the gripper joint

std::vector<double> get_friction_constant_terms()

Get the friction constant terms.

Returns:

Friction constant terms in Nm for arm joints and N for the gripper joint

std::vector<double> get_friction_coulomb_coefs()

Get the friction coulomb coefs.

Returns:

Friction coulomb coefs in Nm/Nm for arm joints and N/N for the gripper joint

std::vector<double> get_friction_viscous_coefs()

Get the friction viscous coefs.

Returns:

Friction viscous coefs in Nm/(rad/s) for arm joints and N/(m/s) for the gripper joint

std::vector<double> get_position_offsets()

Get the position offsets.

Returns:

Position offsets in rad for arm joints and m for the gripper joint

std::string get_error_information()

Get the error information of the robot.

Returns:

Error information

std::vector<Mode> get_modes()

Get the modes.

Returns:

Modes of all joints, a vector of Modes

EndEffector get_end_effector()

Get the end effector properties.

Returns:

The end effector properties

std::vector<JointLimit> get_joint_limits()

Get the joint limits.

Returns:

Joint limits of all joints

std::vector<std::map<Mode, MotorParameter>> get_motor_parameters()

Get the motor parameters.

Returns:

Motor parameters of all modes of all joints

AlgorithmParameter get_algorithm_parameter()

Get the algorithm parameter.

Returns:

Parameter used for robotic algorithms

bool get_is_configured()

Get the configured status of the robot.

Returns:

true The robot is configured

Returns:

false The robot is not configured

void set_log_level(LogLevel level)

Set this driver’s minimum log level.

Messages below this level are silently dropped before reaching the backend.

Parameters:

level – Minimum log level

Public Static Functions

static void set_logger_backend(LogCallback callback)

Set a custom logger backend.

If not called, the library logs to stderr (C++) or Python’s logging module (Python).

Parameters:

callback – A callback invoked for each log message with (level, logger_name, message)

static std::string get_logger_name(Model model, const std::string &serv_ip)

Get the logger name.

Parameters:
  • model – Model of the robot

  • serv_ip – IP address of the robot

Returns:

Logger name

static std::string get_default_logger_name()

Get the default logger name.

Returns:

Default logger name

static std::vector<DiscoverResult> discover(const std::string &subnet, uint8_t ip_start = 1, uint8_t ip_end = 254, double timeout = 0.01)

Discover connected arm controllers on a subnet.

Parameters:
  • subnet – Subnet prefix

  • ip_start – First host octet to probe, default 1

  • ip_end – Last host octet to probe, default 254

  • timeout – Per-host connection timeout in seconds, default 0.01s

Returns:

Vector of DiscoverResult for each arm that responded

static void disable_notice(Notice notice)

Disable a notice.

Parameters:

notice – The notice to disable