Class TrossenArmDriver

Class Documentation

class TrossenArmDriver

Trossen Arm Driver.

Public Functions

~TrossenArmDriver()

Destroy the Trossen Arm Driver object.

void configure(Model model, EndEffectorProperties end_effector, const std::string serv_ip, bool clear_error)

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

void cleanup()

Cleanup the driver.

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

Set the positions of all joints.

Note

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

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, default zeros

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

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

Set the positions of the arm joints.

Note

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

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, default zeros

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

void set_gripper_position(float goal_position, float goal_time = 2.0f, bool blocking = true, float goal_feedforward_velocity = 0.0f, float goal_feedforward_acceleration = 0.0f)

Set the position of the gripper.

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, default zero

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

void set_joint_position(uint8_t joint_index, float goal_position, float goal_time = 2.0f, bool blocking = true, float goal_feedforward_velocity = 0.0f, float goal_feedforward_acceleration = 0.0f)

Set the position of a joint.

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, default zero

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

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

Set the velocities of all joints.

Note

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

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, default zeros

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

Set the velocities of the arm joints.

Note

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

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, default zeros

void set_gripper_velocity(float goal_velocity, float goal_time = 2.0f, bool blocking = true, float goal_feedforward_acceleration = 0.0f)

Set the velocity of the gripper.

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, default zero

void set_joint_velocity(uint8_t joint_index, float goal_velocity, float goal_time = 2.0f, bool blocking = true, float goal_feedforward_acceleration = 0.0f)

Set the velocity of a joint.

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, default zero

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

Set the external efforts of all joints.

Note

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

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<float> &goal_external_efforts, float goal_time = 2.0f, bool blocking = true)

Set the external efforts of the arm joints.

Note

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

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(float goal_external_effort, float goal_time = 2.0f, bool blocking = true)

Set the external effort of the gripper.

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, float goal_external_effort, float goal_time = 2.0f, bool blocking = true)

Set the external effort of a joint.

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 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.5, 2.0]

  • friction_transition_velocity: positive

  • continuity_factor: [1.0, 10.0]

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<float> &effort_corrections)

Set the effort corrections.

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.5, 2.0]

Parameters:

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

void set_friction_transition_velocities(const std::vector<float> &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<float> &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<float> &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<float> &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_continuity_factors(const std::vector<float> &continuity_factors)

Set the continuity factors.

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 [1.0, 10.0]

Parameters:

continuity_factors – Continuity factors in 1 that scales the base continuity constraint

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

Set the modes of each joint.

  • Mode::idle

  • Mode::position

  • Mode::velocity

  • Mode::external_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

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

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

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 EndEffectorProperties &end_effector)

Set the end effector properties.

Parameters:

end_effector – The end effector properties

void set_gripper_force_limit_scaling_factor(float scaling_factor = 0.5f)

Set the gripper force limit scaling factor.

Note

It must be within [0.0, 1.0], 0.0 for no force, 1.0 for max force in the specifications

Parameters:

scaling_factor – Scaling factor for the max gripper force

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

std::vector<float> get_positions()

Get the positions.

Returns:

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

std::vector<float> get_velocities()

Get the velocities.

Returns:

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

std::vector<float> get_efforts()

Get the efforts.

Returns:

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

std::vector<float> get_external_efforts()

Get the external efforts.

Returns:

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

std::vector<float> get_compensation_efforts()

Get the compensation efforts.

Returns:

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

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<float> get_effort_corrections()

Get the effort corrections.

Returns:

Effort corrections in motor effort unit / Nm or N

std::vector<float> 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<float> 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<float> 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<float> 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<float> get_continuity_factors()

Get the continuity factors.

Returns:

Continuity factors in 1 that scales the base continuity constraint

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

EndEffectorProperties get_end_effector()

Get the end effector mass properties.

Returns:

The end effector mass property structure

float get_gripper_force_limit_scaling_factor()

Get the gripper force limit scaling factor.

Returns:

Scaling factor for the max gripper force, 0.0 for no force, 1.0 for max force in the specifications