Program Listing for File trossen_arm.hpp
↰ Return to documentation for file (include/libtrossen_arm/trossen_arm.hpp
)
// Copyright 2025 Trossen Robotics
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
//
// * Neither the name of the the copyright holder nor the names of its
// contributors may be used to endorse or promote products derived from
// this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.
#ifndef LIBTROSSEN_ARM__TROSSEN_ARM_HPP_
#define LIBTROSSEN_ARM__TROSSEN_ARM_HPP_
#include <cstdint>
#include <array>
#include <atomic>
#include <map>
#include <memory>
#include <mutex>
#include <optional>
#include <string>
#include <thread>
#include <variant>
#include <vector>
#include "libtrossen_arm/trossen_arm_type.hpp"
namespace trossen_arm
{
class QuinticHermiteInterpolator;
class EthernetManager;
class AlgorithmInterface;
struct StandardEndEffector {
static constexpr EndEffector wxai_v0_base{
.palm = {
.mass = 0.53780000,
.inertia = {
0.00079919, -0.00000049, 0.00000010,
-0.00000049, 0.00047274, 0.00000004,
0.00000010, 0.00000004, 0.00105293
},
.origin_xyz = {0.04572768, -0.00000726, 0.00001402},
.origin_rpy = {0.0, 0.0, 0.0}
},
.finger_left = {
.mass = 0.05945000,
.inertia = {
0.00001875, 0.00000309, -0.00000149,
0.00000309, 0.00002614, -0.00000124,
-0.00000149, -0.00000124, 0.00002995
},
.origin_xyz = {0.00169016, -0.00592796, -0.00365701},
.origin_rpy = {0.0, 0.0, 0.0}
},
.finger_right = {
.mass = 0.05945000,
.inertia = {
0.00001930, -0.00000309, 0.00000359,
-0.00000309, 0.00002670, -0.00000064,
0.00000359, -0.00000064, 0.00002995
},
.origin_xyz = {0.00169015, 0.00592793, 0.00201818},
.origin_rpy = {0.0, 0.0, 0.0}
},
.offset_finger_left = 0.0227,
.offset_finger_right = -0.0227,
.pitch_circle_radius = 0.00875,
.t_flange_tool = {0.154, 0.0, 0.0, 0.0, 0.0, 0.0}
};
static constexpr EndEffector wxai_v0_leader{
.palm = {
.mass = 0.59570000,
.inertia = {
0.00117653, -0.00000040, -0.00005492,
-0.00000040, 0.00085696, 0.00000074,
-0.00005492, 0.00000074, 0.00107685
},
.origin_xyz = {0.04454388, 0.00000506, -0.00694150},
.origin_rpy = {0.0, 0.0, 0.0}
},
.finger_left = {
.mass = 0.06380000,
.inertia = {
0.00003556, -0.00000249, 0.00000167,
-0.00000249, 0.00002700, 0.00000217,
0.00000167, 0.00000217, 0.00001726
},
.origin_xyz = {-0.00423580, -0.00167541, -0.01050810},
.origin_rpy = {0.0, 0.0, 0.0}
},
.finger_right = {
.mass = 0.06380000,
.inertia = {
0.00004133, 0.00000250, 0.00000517,
0.00000250, 0.00003277, -0.00000592,
0.00000517, -0.00000592, 0.00001727
},
.origin_xyz = {-0.00423309, 0.00167373, -0.00451087},
.origin_rpy = {0.0, 0.0, 0.0}
},
.offset_finger_left = 0.0179,
.offset_finger_right = -0.0179,
.pitch_circle_radius = 0.00875,
.t_flange_tool = {0.154, 0.0, 0.0, 0.0, 0.0, 0.0}
};
static constexpr EndEffector wxai_v0_follower{
.palm = {
.mass = 0.64230000,
.inertia = {
0.00108484, 0.00000063, -0.00004180,
0.00000063, 0.00075170, -0.00001558,
-0.00004180, -0.00001558, 0.00110994
},
.origin_xyz = {0.04699592, 0.00045936, 0.00827772},
.origin_rpy = {0.0, 0.0, 0.0}
},
.finger_left = {
.mass = 0.05945000,
.inertia = {
0.00001875, 0.00000309, -0.00000149,
0.00000309, 0.00002614, -0.00000124,
-0.00000149, -0.00000124, 0.00002995
},
.origin_xyz = {0.00169016, -0.00592796, -0.00365701},
.origin_rpy = {0.0, 0.0, 0.0}
},
.finger_right = {
.mass = 0.05945000,
.inertia = {
0.00001930, -0.00000309, 0.00000359,
-0.00000309, 0.00002670, -0.00000064,
0.00000359, -0.00000064, 0.00002995
},
.origin_xyz = {0.00169015, 0.00592793, 0.00201818},
.origin_rpy = {0.0, 0.0, 0.0}
},
.offset_finger_left = 0.0227,
.offset_finger_right = -0.0227,
.pitch_circle_radius = 0.00875,
.t_flange_tool = {0.154, 0.0, 0.0, 0.0, 0.0, 0.0}
};
};
class TrossenArmDriver
{
public:
TrossenArmDriver();
~TrossenArmDriver();
void configure(
Model model,
EndEffector end_effector,
const std::string serv_ip,
bool clear_error,
double timeout = 20.0
);
void cleanup(bool reboot_controller = false);
inline void reboot_controller()
{
cleanup(true);
}
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);
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);
void set_gripper_position(
double goal_position,
double goal_time = 2.0,
bool blocking = true,
double goal_feedforward_velocity = 0.0,
double goal_feedforward_acceleration = 0.0);
void set_joint_position(
uint8_t joint_index,
double goal_position,
double goal_time = 2.0,
bool blocking = true,
double goal_feedforward_velocity = 0.0,
double goal_feedforward_acceleration = 0.0
);
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
);
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);
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);
void set_gripper_velocity(
double goal_velocity,
double goal_time = 2.0,
bool blocking = true,
double goal_feedforward_acceleration = 0.0
);
void set_joint_velocity(
uint8_t joint_index,
double goal_velocity,
double goal_time = 2.0,
bool blocking = true,
double goal_feedforward_acceleration = 0.0
);
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
);
void set_all_external_efforts(
const std::vector<double> & goal_external_efforts,
double goal_time = 2.0,
bool blocking = true
);
void set_arm_external_efforts(
const std::vector<double> & goal_external_efforts,
double goal_time = 2.0,
bool blocking = true
);
void set_gripper_external_effort(
double goal_external_effort,
double goal_time = 2.0,
bool blocking = true
);
void set_joint_external_effort(
uint8_t joint_index,
double goal_external_effort,
double goal_time = 2.0,
bool blocking = 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
);
void set_all_efforts(
const std::vector<double> & goal_efforts,
double goal_time = 2.0,
bool blocking = true
);
void set_arm_efforts(
const std::vector<double> & goal_efforts,
double goal_time = 2.0,
bool blocking = true
);
void set_gripper_effort(
double goal_effort,
double goal_time = 2.0,
bool blocking = true
);
void set_joint_effort(
uint8_t joint_index,
double goal_effort,
double goal_time = 2.0,
bool blocking = true
);
void load_configs_from_file(const std::string & file_path);
void set_factory_reset_flag(bool flag = true);
void set_ip_method(IPMethod method = IPMethod::manual);
void set_manual_ip(const std::string manual_ip = "192.168.1.2");
void set_dns(const std::string dns = "8.8.8.8");
void set_gateway(const std::string gateway = "192.168.1.1");
void set_subnet(const std::string subnet = "255.255.255.0");
void set_joint_characteristics(const std::vector<JointCharacteristic> & joint_characteristics);
void set_effort_corrections(const std::vector<double> & effort_corrections);
void set_friction_transition_velocities(
const std::vector<double> & friction_transition_velocities
);
void set_friction_constant_terms(const std::vector<double> & friction_constant_terms);
void set_friction_coulomb_coefs(const std::vector<double> & friction_coulomb_coefs);
void set_friction_viscous_coefs(const std::vector<double> & friction_viscous_coefs);
void set_joint_modes(const std::vector<Mode> & modes);
void set_all_modes(Mode mode = Mode::idle);
void set_arm_modes(Mode mode = Mode::idle);
void set_gripper_mode(Mode mode = Mode::idle);
void set_end_effector(const EndEffector & end_effector);
void set_joint_limits(const std::vector<JointLimit> & joint_limits);
void set_motor_parameters(const std::vector<std::map<Mode, MotorParameter>> & motor_parameters);
void set_algorithm_parameter(const AlgorithmParameter & algorithm_parameter);
uint8_t get_num_joints() const;
const std::string & get_driver_version() const;
const std::string & get_controller_version() const;
const RobotOutput & get_robot_output();
[[deprecated(
"get_positions will be deprecated in the next version, "
"please use get_all_positions instead"
)]]
const std::vector<double> & get_positions();
const std::vector<double> & get_all_positions();
const std::vector<double> & get_arm_positions();
double get_gripper_position();
double get_joint_position(uint8_t joint_index);
const std::array<double, 6> & get_cartesian_positions();
[[deprecated(
"get_velocities will be deprecated in the next version, "
"please use get_all_velocities instead"
)]]
const std::vector<double> & get_velocities();
const std::vector<double> & get_all_velocities();
const std::vector<double> & get_arm_velocities();
double get_gripper_velocity();
double get_joint_velocity(uint8_t joint_index);
const std::array<double, 6> & get_cartesian_velocities();
const std::vector<double> & get_all_accelerations();
const std::vector<double> & get_arm_accelerations();
double get_gripper_acceleration();
double get_joint_acceleration(uint8_t joint_index);
const std::array<double, 6> & get_cartesian_accelerations();
[[deprecated(
"get_efforts will be deprecated in the next version, "
"please use get_all_efforts instead"
)]]
const std::vector<double> & get_efforts();
const std::vector<double> & get_all_efforts();
const std::vector<double> & get_arm_efforts();
double get_gripper_effort();
double get_joint_effort(uint8_t joint_index);
[[deprecated(
"get_external_efforts will be deprecated in the next version, "
"please use get_all_external_efforts instead"
)]]
const std::vector<double> & get_external_efforts();
const std::vector<double> & get_all_external_efforts();
const std::vector<double> & get_arm_external_efforts();
double get_gripper_external_effort();
double get_joint_external_effort(uint8_t joint_index);
const std::array<double, 6> & get_cartesian_external_efforts();
[[deprecated(
"get_compensation_efforts will be deprecated in the next version, "
"please use get_all_compensation_efforts instead"
)]]
const std::vector<double> & get_compensation_efforts();
const std::vector<double> & get_all_compensation_efforts();
const std::vector<double> & get_arm_compensation_efforts();
double get_gripper_compensation_effort();
double get_joint_compensation_effort(uint8_t joint_index);
const std::vector<double> & get_all_rotor_temperatures();
const std::vector<double> & get_arm_rotor_temperatures();
double get_gripper_rotor_temperature();
double get_joint_rotor_temperature(uint8_t joint_index);
const std::vector<double> & get_all_driver_temperatures();
const std::vector<double> & get_arm_driver_temperatures();
double get_gripper_driver_temperature();
double get_joint_driver_temperature(uint8_t joint_index);
void save_configs_to_file(const std::string & file_path);
bool get_factory_reset_flag();
IPMethod get_ip_method();
std::string get_manual_ip();
std::string get_dns();
std::string get_gateway();
std::string get_subnet();
std::vector<JointCharacteristic> get_joint_characteristics();
std::vector<double> get_effort_corrections();
std::vector<double> get_friction_transition_velocities();
std::vector<double> get_friction_constant_terms();
std::vector<double> get_friction_coulomb_coefs();
std::vector<double> get_friction_viscous_coefs();
std::string get_error_information();
std::vector<Mode> get_modes();
EndEffector get_end_effector();
std::vector<JointLimit> get_joint_limits();
std::vector<std::map<Mode, MotorParameter>> get_motor_parameters();
AlgorithmParameter get_algorithm_parameter();
private:
// Raw counterpart of JointCharacteristic
struct JointCharacteristicRaw
{
float effort_correction;
float friction_transition_velocity;
float friction_constant_term;
float friction_coulomb_coef;
float friction_viscous_coef;
void to_raw(const JointCharacteristic & joint_characteristic);
JointCharacteristic from_raw() const;
};
// Raw counterpart of Link
struct LinkRaw
{
float mass;
float inertia[9];
float origin_xyz[3];
float origin_rpy[3];
void to_raw(const Link & link);
Link from_raw() const;
};
// Raw counterpart of EndEffector
struct EndEffectorRaw
{
LinkRaw palm;
LinkRaw finger_left;
LinkRaw finger_right;
float offset_finger_left;
float offset_finger_right;
float pitch_circle_radius;
void to_raw(const EndEffector & end_effector);
EndEffector from_raw() const;
};
// Raw counterpart of JointLimit
struct JointLimitRaw
{
float position_min;
float position_max;
float position_tolerance;
float velocity_max;
float velocity_tolerance;
float effort_max;
float effort_tolerance;
void to_raw(const JointLimit & joint_limit);
JointLimit from_raw() const;
};
// Raw counterpart of PIDParameter
struct PIDParameterRaw
{
float kp;
float ki;
float kd;
float imax;
void to_raw(const PIDParameter & pid_parameter);
PIDParameter from_raw() const;
};
// Raw counterpart of MotorParameter
struct MotorParameterRaw
{
PIDParameterRaw position;
PIDParameterRaw velocity;
void to_raw(const MotorParameter & motor_parameter);
MotorParameter from_raw() const;
};
struct JointInputRaw
{
Mode mode{Mode::idle};
union Command {
struct Position {
float position;
float feedforward_velocity;
float feedforward_acceleration;
} position{0.0f, 0.0f, 0.0f};
struct Velocity {
float velocity;
float feedforward_acceleration;
} velocity;
struct ExternalEffort {
float external_effort;
} external_effort;
struct Effort {
float effort;
} effort;
} command;
};
struct JointOutputRaw
{
float position;
float velocity;
float effort;
float external_effort;
float rotor_temperature;
float driver_temperature;
};
struct RobotInput
{
struct Joint
{
struct All
{
std::vector<double> positions;
std::vector<double> velocities;
std::vector<double> accelerations;
std::vector<double> efforts;
std::vector<double> external_efforts;
} all;
struct Arm
{
std::vector<double> positions;
std::vector<double> velocities;
std::vector<double> accelerations;
std::vector<double> efforts;
std::vector<double> external_efforts;
} arm;
struct Gripper
{
double position;
double velocity;
double acceleration;
double effort;
double external_effort;
} gripper;
} joint;
struct Cartesian
{
std::array<double, 6> positions;
std::array<double, 6> velocities;
std::array<double, 6> accelerations;
std::array<double, 6> external_efforts;
} cartesian;
};
struct RobotCommandIndicator
{
enum class UDP : uint8_t
{
set_robot_input,
get_robot_output
};
enum class TCP : uint8_t
{
handshake,
set_home,
set_configuration,
get_configuration,
get_log,
update_default_eeprom,
reboot
};
};
// ErrorState
enum class ErrorState : uint8_t {
// No error
none,
// Controller's Ethernet manager failed to initialize
ethernet_init_failed,
// Controller's CAN interface failed to initialize
can_init_failed,
// Controller's CAN interface failed to send a message
joint_command_failed,
// Controller's CAN interface failed to receive a message
joint_feedback_failed,
// Joint clear error command failed
joint_clear_error_failed,
// Joint enable command failed
joint_enable_failed,
// Joint disable command failed
joint_disable_failed,
// Joint home calibration command failed
joint_set_home_failed,
// Joint disabled unexpectedly
joint_disabled_unexpectedly,
// Joint overheated
joint_overheated,
// Invalid mode command received
invalid_mode,
// Invalid robot command indicator received
invalid_robot_command,
// Invalid configuration address
invalid_configuration_address,
// Robot input with modes different than configured modes received
robot_input_mode_mismatch,
// Joint limit exceeded
joint_limit_exceeded,
// Robot input infinite
robot_input_infinite
};
// Configuration addresses
enum class ConfigurationAddress : uint8_t {
// Controller configurations
factory_reset_flag,
ip_method,
manual_ip,
dns,
gateway,
subnet,
joint_characteristics,
error_state,
modes,
end_effector,
joint_limits,
motor_parameters,
// Local configurations
algorithm_parameter,
};
// Maximum retransmission attempts
static constexpr uint8_t MAX_RETRANSMISSION_ATTEMPTS{100};
// Number of modes
static constexpr uint8_t NUM_MODES{5};
// Model to number of joints mapping
static const std::map<Model, uint8_t> MODEL_NUM_JOINTS;
// Error information
static const std::map<ErrorState, std::string> ERROR_INFORMATION;
// Model name
static const std::map<Model, std::string> MODEL_NAME;
// Mode name
static const std::map<Mode, std::string> MODE_NAME;
// Configuration name
static const std::map<ConfigurationAddress, std::string> CONFIGURATION_NAME;
// Interpolators for joint trajectories
std::vector<std::unique_ptr<QuinticHermiteInterpolator>> trajectory_ptrs_;
// Trajectory start time
std::vector<std::chrono::time_point<std::chrono::steady_clock>> trajectory_start_times_;
// Interpolation space
InterpolationSpace interpolation_space_{InterpolationSpace::joint};
// Joint inputs
std::vector<JointInputRaw> joint_input_raws_;
// Joint outputs
std::vector<JointOutputRaw> joint_output_raws_;
// Number of joints
uint8_t num_joints_{0};
// Driver version
std::string driver_version_;
// Controller firmware version
std::string controller_version_;
// Whether the driver is properly configured for the robot to be controlled
// true if configured, false if not configured
bool configured_{false};
// Ethernet manager
std::unique_ptr<EthernetManager> ethernet_manager_ptr_;
// Atomic flag for maintaining and stopping the daemon thread
std::atomic<bool> activated_{false};
// Multithreading design
//
// Goal
//
// - only one thread can run at a time
// - another thread cannot cut in until the full communication cycle is completed
// for example, set_joint_inputs --nothing-in-between--> receive_joint_outputs
// - the other thread has priority to run after the current thread finishes
//
// Mutex ownership
//
// call mutex_preempt_ 1 and mutex_data_ 2 for simplicity
// daemon: |-|-1-|-12-|-2-|--------|-1-|-12-|-2-|-|
// main: |------------|-1-|-12-|-2-|------------|
//
// Exception handling
//
// - if an exception is thrown in the main thread
// - the daemon thread gets std::terminate
// - the main thread unwind the stack: ~TrossenArmDriver() -> cleanup()
// - if an exception is thrown in the daemon thread
// - the exception is stored in exception_ptr_
// - the daemon thread returns
// - the main thread gets the exception and rethrows it at the next operation
// - the main thread unwind the stack: ~TrossenArmDriver() -> cleanup()
//
// Notes
//
// - the mutex claiming cannot be nested or there will be deadlocks, i.e., |-1-|-12-|-2-|-12-|-2-|
// is not allowed
// - when an exception is thrown by the main thread, the program is expected to terminate either
// immediately or right after cleaning up the resources not related to the driver
// Daemon thread
std::thread daemon_thread_;
// Mutex for data access
std::mutex mutex_data_;
// Mutex for preempting the next slot to run
std::mutex mutex_preempt_;
// Shared exception pointer
std::exception_ptr exception_ptr_;
// Algorithm interface
std::unique_ptr<AlgorithmInterface> algorithm_interface_ptr_;
// Robot input
RobotInput robot_input_;
// Robot output
RobotOutput robot_output_;
// Arm mode
Mode arm_mode_{Mode::idle};
void update_robot_output();
void update_robot_input();
void set_joint_inputs();
bool receive_joint_outputs();
void check_error_state(
const std::vector<uint8_t> & buffer,
bool clear_error
);
void reset_error_state();
std::string get_detailed_log();
using ConfigurationVariant = std::variant<
std::monostate,
bool,
IPMethod,
std::string,
std::vector<JointCharacteristic>,
std::vector<Mode>,
EndEffector,
std::vector<JointLimit>,
std::vector<std::map<Mode, MotorParameter>>,
AlgorithmParameter
>;
void set_configuration(
ConfigurationAddress configuration_address,
const ConfigurationVariant & configuration_variant
);
ConfigurationVariant get_configuration(ConfigurationAddress configuration_address);
void daemon();
};
} // namespace trossen_arm
#endif // LIBTROSSEN_ARM__TROSSEN_ARM_HPP_