ethercatcpp
Classes | Public Types | Public Member Functions | Static Public Member Functions | Static Protected Member Functions | Private Member Functions | Static Private Member Functions | Private Attributes | Static Private Attributes | List of all members
ethercatcpp::SensoJoint Class Reference

This class describe the EtherCAT driver for Sensodrive sensojoint actuator. It allows to communicate with a "Sensodrive Sensojoint actuator" through an ethercat bus managed by an ethercatcpp master. More...

#include <sensojoint.h>

Inheritance diagram for ethercatcpp::SensoJoint:
Inheritance graph

Classes

struct  EndStop
 
struct  Options
 

Public Types

enum  control_mode_t {
  control_mode_t::monitor, control_mode_t::profile_position, control_mode_t::profile_velocity, control_mode_t::profile_torque,
  control_mode_t::cyclic_position, control_mode_t::cyclic_velocity, control_mode_t::cyclic_torque, control_mode_t::profile_output_position_vibration_damping,
  control_mode_t::profile_output_velocity, control_mode_t::cyclic_output_position_vibration_damping, control_mode_t::cyclic_output_velocity, control_mode_t::cyclic_output_torque
}
 This enum define the possible "control modes" of the actuator. More...
 
enum  Model { MODEL_7016, MODEL_5016, MODEL_4010, MODEL_3010 }
 
enum  IOFlag { gpio_3_io_fpp_pin = 1 << 0, gpio_4_out_pin = 1 << 1, gpio_5_io_sbo_pin = 1 << 2, gpio_6_io_sbo_pin = 1 << 3 }
 Flag to ease setting the controlled/read GPIOS. More...
 
using operation_state_t = CIA402Device::state_t
 
- Public Types inherited from ethercatcpp::coe::cia402::CIA402Device
enum  state_t {
  unknown_state, not_ready_to_switch_on, switch_on_disabled, ready_to_switch_on,
  switched_on, operation_enabled, quick_stop_active, fault_reaction_active,
  faulty
}
 Possible state of a CiA402 device state machine. More...
 
enum  control_t {
  shutdown, switch_on, switch_on_and_enable_op, disable_voltage,
  quickstop, disable_op, enable_op, fault_reset_op
}
 Possible control over a CiA402 device state machine. More...
 
- Public Types inherited from ethercatcpp::SlaveDevice
enum  syncmanager_buffer_t { ASYNCHROS_OUT, ASYNCHROS_IN, SYNCHROS_OUT, SYNCHROS_IN = 4 }
 This enum define all type of buffers (SyncManager type) More...
 

Public Member Functions

virtual bool profile_mode () const override
 
virtual bool cyclic_mode () const override
 
virtual bool position_mode () const override
 
virtual bool velocity_mode () const override
 
virtual bool torque_mode () const override
 
virtual bool profile_mode_queried () const override
 
virtual bool cyclic_mode_queried () const override
 
virtual bool position_mode_queried () const override
 
virtual bool velocity_mode_queried () const override
 
virtual bool torque_mode_queried () const override
 
 SensoJoint (const Model &model)
 Constructor of SensoJoint class. More...
 
 SensoJoint (const Model &model, const Options &options)
 
 SensoJoint (const SensoJoint &)=delete
 
 SensoJoint (SensoJoint &&)=delete
 
SensoJointoperator= (const SensoJoint &)=delete
 
SensoJointoperator= (SensoJoint &&)=delete
 
virtual ~SensoJoint ()
 
void set_target_position (double target_position)
 Function used to set the target position when device is command in position mode. More...
 
void set_target_velocity (double target_velocity)
 Function used to set the target velocity when device is command in velocity mode. More...
 
void set_target_output_torque (double target_torque)
 Function used to set the target torque on output shaft when device is command in output or basic torque modes. More...
 
void set_target_motor_torque (double target_torque)
 Function used to set the target motor torque when device is command in basic torque mode. More...
 
void set_motor_torque_feedforward (double torque_offset)
 Function used to set the motor torque offset. More...
 
void set_output_torque_feedforward (double torque_offset)
 Function used to set the output torque offset. More...
 
void set_external_load_torque_offset (double offset)
 Set value of external load torque offset (gravity) More...
 
void set_velocity_feedforward (double velocity_offset)
 Function used to set the velocity offset. More...
 
bool set_control_mode (control_mode_t control_mode)
 Select the desired control mode. More...
 
control_mode_t control_mode () const
 Get current control mode used inside device. More...
 
std::string_view control_mode_str () const
 Get current control mode used inside device as a string. More...
 
double position () const
 Get actual motor position in radians. More...
 
double velocity () const
 Get actual motor velocity in radians per second. More...
 
double motor_torque () const
 Get actual motor torque in newton meter. More...
 
double motor_current () const
 Get actual motor current in A. More...
 
double output_torque () const
 Get actual output torque in newton meter (Nm). More...
 
double friction_torque () const
 Get actual friction torque in newton meter (Nm). More...
 
double motor_temperature () const
 Get actual motor temperature in degrees celsius (°C). More...
 
double drive_temperature () const
 Get actual drive temperature in degrees celsius (°C). More...
 
double sensor_temperature () const
 Get actual torque sensor temperature in degrees celsius (°C). More...
 
bool following_error () const
 In profile modes tell whether there is a following error. More...
 
bool standstill () const
 In profile velocity modes tell whether the motor is standstill. More...
 
bool sto_active () const
 Check whether STO(Safe torque off) security has been triggerred. More...
 
bool sbc_active () const
 Check whether SBC(Safe braque control) security has been triggerred. More...
 
bool brake_applied () const
 Tell whether Sensojoint brake is applied. More...
 
const Optionsoptions () const
 Get options used in the Sensojoint. More...
 
const std::string & fault () const
 Get last fault description. More...
 
uint16_t error_code () const
 Get last error code. More...
 
bool warning () const
 check if a warning is currently emitted. More...
 
void set_spring (double neutral_position, double stiffness, double damping)
 Set value of spring haptics effect parameters in advanced torque controller. More...
 
void set_digital_outputs (uint8_t outputs)
 Set value of digital outputs. More...
 
uint8_t digital_inputs () const
 Get value of digital inputs. More...
 
double initial_position () const
 Get the theoric initial position from drive configuration. More...
 
- Public Member Functions inherited from ethercatcpp::coe::cia402::CIA402Device
 CIA402Device (uint16_t &control_word, uint16_t &status_word, int8_t &mode_set, int8_t &mode_read)
 
 CIA402Device ()
 
virtual ~CIA402Device ()
 
state_t operation_state () const
 get current state of the device. More...
 
std::string_view operation_state_str () const
 get string representation of current state of the device. More...
 
void acknowledge_fault ()
 Acknowledge fault and reset faulty status. More...
 
void quick_stop ()
 Launch the quick stop procedure. More...
 
bool voltage_enabled () const
 Tell whether device is powered with high voltage. More...
 
bool fault_alert () const
 Tell whether device reports an error. More...
 
bool warning_alert () const
 Tell whether device reports a warning. More...
 
bool is_configurable () const
 Tell whether the sensojoint can be immediately configured. More...
 
bool process_state ()
 Perform adequate operations depending on state. More...
 
void startup ()
 Make sensojoint controlable and control mode cannot be changed. More...
 
void finish ()
 Put the sensojoint is a safe, configuration possible, state. More...
 
void pause (bool doit)
 State transition is paused/unpaused. More...
 
bool active () const
 Tell whether the sensojoint is active (is running or will run commands) or not (is or will be in a safe state, where control mode can be configured) More...
 
bool paused () const
 Tell whether the device state transition is paused. More...
 
bool target_reached () const
 Tell whether the target given by a profile mode has been reached. More...
 
bool manage_new_setpoint ()
 Make the controller manage a new setpoint (e.g. value of target position). Only in profile mode. More...
 
bool motion_halted () const
 Tell whether motion generated by a profile mode is halted. More...
 
void halt_motion (bool choice)
 Halt motor axle, only in profile mode. More...
 
bool new_setpoint_following () const
 Tell whether a new set point is tracked. Only in profile position mode. More...
 
bool internal_limit () const
 In profile modes tell whether there is an internal limit has been reached. More...
 
void reset_fault ()
 Reset fault so that the device can start again. More...
 
- Public Member Functions inherited from ethercatcpp::SlaveDevice
 SlaveDevice ()
 Constructor of SlaveDevice class. More...
 
virtual ~SlaveDevice ()
 
void set_serial_number (uint32_t serial_number)
 Set the serial number of the device. More...
 
uint32_t eep_manufacturer () const
 Get EtherCAT device manufacturer id. More...
 
uint32_t eep_device () const
 Get EtherCAT device id. More...
 
uint32_t serial_number () const
 Get device serial number. More...
 
- Public Member Functions inherited from ethercatcpp::Device
 Device ()
 
virtual ~Device ()
 

Static Public Member Functions

static SensoJoint::Options gen_options (double control_period, double min_target_pos, double max_target_pos)
 
static bool is_advanced_mode (control_mode_t)
 
static bool is_profile_mode (control_mode_t)
 
static bool is_cyclic_mode (control_mode_t)
 
static bool is_position_mode (control_mode_t)
 
static bool is_velocity_mode (control_mode_t)
 
static bool is_torque_mode (control_mode_t)
 
static std::string_view control_mode_to_str (control_mode_t)
 convert the operation state into a human readable information More...
 
- Static Public Member Functions inherited from ethercatcpp::coe::cia402::CIA402Device
static void set_control_word (uint16_t &controlword, control_t ctrl)
 Set the control word of a CiA402 device according to the desired control state. More...
 
static state_t operation_state (uint16_t statusword)
 Get the current state according to the data in the statusword. More...
 
static std::string_view operation_state_to_str (state_t)
 convert the operation state into a human readable information More...
 
static std::string_view control_mode_to_str (int8_t)
 convert the control mode into a human readable information More...
 

Static Protected Member Functions

static bool advanced_mode (int8_t)
 
static bool profile_mode (int8_t)
 
static bool cyclic_mode (int8_t)
 
static bool position_mode (int8_t)
 
static bool velocity_mode (int8_t)
 
static bool torque_mode (int8_t)
 
- Static Protected Member Functions inherited from ethercatcpp::coe::cia402::CIA402Device
static bool profile_mode (int8_t)
 
static bool cyclic_mode (int8_t)
 
static bool position_mode (int8_t)
 
static bool velocity_mode (int8_t)
 
static bool torque_mode (int8_t)
 

Private Member Functions

void initialize (const std::optional< Options > &options)
 
void pdo_maps_configuration ()
 
void unpack_status_buffer ()
 
void update_internal_state ()
 
void read_base_units_values ()
 
void find_initial_position ()
 
void manage_ctrl_params (const std::optional< Options > &options)
 
void bind_buffers ()
 
void manage_control_period (const std::optional< Options > &options)
 
void manage_torque_slope (const std::optional< Options > &options)
 
void manage_torque_offset (const std::optional< Options > &options)
 
void manage_position_offset (const std::optional< Options > &options)
 
void manage_max_output_torque ()
 
void manage_max_output_velocity ()
 
void manage_max_motor_torque ()
 
void manage_max_motor_current ()
 
void manage_max_motor_velocity ()
 
void manage_user_max_motor_torque (const std::optional< Options > &options)
 
void manage_user_max_motor_velocity (const std::optional< Options > &options)
 
void manage_user_position_limits (const std::optional< Options > &options)
 
void manage_quickstop_config (const std::optional< Options > &options)
 
void manage_profile_config (const std::optional< Options > &options)
 
void manage_endstop_config (const std::optional< Options > &options)
 
void manage_digital_ios (const std::optional< Options > &options)
 
void manage_digital_ios_end ()
 
void manage_torque_based_quick_stop ()
 
void force_target_output_torque (double target_torque)
 
void force_target_motor_torque (double target_torque)
 

Static Private Member Functions

static int8_t control_mode_to_code (control_mode_t)
 
static control_mode_t control_code_to_mode (int8_t)
 
static bool can_swap_mode (control_mode_t current, control_mode_t next)
 

Private Attributes

Options options_
 
Model model_
 
std::unique_ptr< OpaqueStateCommands > sta_cmd_
 
std::unique_ptr< InternalParameters > internal_parameters_
 
std::unique_ptr< ConversionRatios > conversion_
 

Static Private Attributes

static const std::map< int8_t, std::string_view > control_mode_decode_
 

Additional Inherited Members

- Static Public Attributes inherited from ethercatcpp::coe::cia402::CIA402Device
static constexpr const uint16_t controlword_addr = 0x6040
 
static constexpr const uint16_t statusword_addr = 0x6041
 
static constexpr const uint16_t set_modes_of_operation_addr = 0x6060
 
static constexpr const uint16_t get_modes_of_operation_addr = 0x6061
 
static constexpr const uint16_t not_ready_to_switch_on_code = 0x0000
 
static constexpr const uint16_t switch_on_disabled_code = 0x0040
 
static constexpr const uint16_t ready_to_switch_on_code = 0x0021
 
static constexpr const uint16_t switched_on_code = 0x0023
 
static constexpr const uint16_t operation_enabled_code = 0x0027
 
static constexpr const uint16_t quick_stop_active_code = 0x0007
 
static constexpr const uint16_t fault_reaction_active_code = 0x000F
 
static constexpr const uint16_t fault_code = 0x0008
 
static constexpr const int8_t monitor_mode = 0
 
static constexpr const int8_t PP_mode = 1
 Profile position. More...
 
static constexpr const int8_t PV_mode = 3
 Profile velocity. More...
 
static constexpr const int8_t PT_mode = 4
 Profile torque. More...
 
static constexpr const int8_t HOMING_mode = 6
 Homing. More...
 
static constexpr const int8_t IP_mode = 7
 Profile interpolated. More...
 
static constexpr const int8_t CSP_mode = 8
 Cyclic synchronous position. More...
 
static constexpr const int8_t CSV_mode = 9
 Cyclic synchronous velocity. More...
 
static constexpr const int8_t CST_mode = 10
 Cyclic synchronous torque. More...
 
static const std::map< state_t, std::string_view > device_state_decode_
 
- Protected Member Functions inherited from ethercatcpp::coe::cia402::CIA402Device
void set_operation_state (control_t state)
 Function used to change the state of device. More...
 
void set_quick_stop_reaction (std::function< void()> reaction)
 Set the quick stop reaction function called when a quick stop procedure starts. More...
 
void set_leaving_enable_requires_quick_stop (std::function< bool()> check_quick_stop)
 Set the check function called when device leaves the operation enabled state. More...
 
void set_entering_enable_reaction (std::function< bool()> reaction)
 Set the reaction function called when device enters the operation enabled state. More...
 
void set_entering_switchon_reaction (std::function< void()> reaction)
 Set the reaction function called when device enters the switched on state. More...
 
void set_entering_disabled_reaction (std::function< void()> reaction)
 Set the reaction function called when device enters the switched on disabled state. More...
 
void initialize_state_variables (uint16_t &control_word, uint16_t &status_word, int8_t &mode_set, int8_t &mode_read)
 Set the variables used to control the state machine. More...
 
void initialize_state_variables (uint16_t *control_word, uint16_t *status_word, int8_t *mode_set, int8_t *mode_read)
 Set the variables used to control the state machine. More...
 
void initialize_state_variables (uint8_t *control_word_addr, uint8_t *status_word_addr, uint8_t *mode_set_addr, uint8_t *mode_read_addr)
 Set the variables used to control the state machine. More...
 
int8_t current_control_mode () const
 Utility function for implementing the control_mode() function of derived classes. More...
 
void device_state_termination ()
 Performs operations supposed to put the device in a safe state. More...
 
void device_state_initialization ()
 Performs operations supposed to put the device in a safe state. More...
 
void managed_set_point ()
 Ask the device to take into account the new set point given. Only in profile position modes. More...
 
- Protected Member Functions inherited from ethercatcpp::SlaveDevice
template<typename T , typename... U>
void define_physical_buffer (syncmanager_buffer_t type, uint16_t start_addr, uint32_t flags)
 Define a physical buffer (EtherCAT syncManager buffer). More...
 
void define_physical_buffer (syncmanager_buffer_t type, uint16_t start_addr, uint32_t flags, uint16_t length)
 Define a physical buffer (EtherCAT syncManager buffer). More...
 
template<typename T >
T * input_buffer (uint16_t start_addr)
 Get data of input physical buffer. More...
 
template<typename T , typename U , typename... Other>
std::tuple< T *, U *, Other *... > input_buffer (uint16_t start_addr)
 
uint8_t * input_buffer (uint16_t start_addr)
 Get data of input physical buffer. More...
 
template<typename T >
T * output_buffer (uint16_t start_addr)
 Get data of output physical buffer. More...
 
template<typename T , typename U , typename... Other>
std::tuple< T *, U *, Other *... > output_buffer (uint16_t start_addr)
 
uint8_t * output_buffer (uint16_t start_addr)
 Get data of output physical buffer. More...
 
void add_run_step (std::function< void()> &&pre, std::function< void()> &&post)
 Add a run step and define pre_function and post_function run step. More...
 
void add_init_step (std::function< void()> &&pre, std::function< void()> &&post)
 Add a init step and define pre_function and post_function for this init step. More...
 
void add_end_step (std::function< void()> &&pre, std::function< void()> &&post)
 Add a end step and define pre_function and post_function for this end step. More...
 
void set_id (const std::string &name, uint32_t manufacturer, uint32_t model)
 Set a specific ID to the slave. More...
 
void define_distributed_clock (bool have_dc)
 Define if the slave have a distributed clock. More...
 
void define_period_for_non_cyclic_steps (int period)
 Define the period between two non cyclic steps. More...
 
void configure_at_init (std::function< void()> &&func)
 Define the function that configures the slave in PREOP state at initialization of the ethercat bus (Master::init()) . More...
 
void configure_at_end (std::function< void()> &&func)
 Define the function that performs configuration actions in PREOP state at termination of the ethercat bus. (Master::end()). More...
 
int write_sdo (uint16_t index, uint8_t sub_index, int buffer_size, void *buffer) const
 write a SDO capable object field More...
 
int read_sdo (uint16_t index, uint8_t sub_index, int buffer_size, void *buffer) const
 read a SDO capable object field More...
 
template<typename T >
int write_sdo (uint16_t index, uint8_t sub_index, T &value) const
 Send a CoE write SDO packet to the slave. More...
 
template<typename T >
int read_sdo (uint16_t index, uint8_t sub_index, T &value) const
 Send a CoE read SDO packet to the slave. More...
 
template<typename T >
bool start_command_pdo_mapping ()
 Start the definition of the command PDO mapping. More...
 
template<typename T >
bool add_command_pdo_mapping (uint16_t pdo_address)
 Add a new command PDO map link. More...
 
template<typename T >
bool end_command_pdo_mapping ()
 Finish the definition of the command PDO mapping. More...
 
template<typename T >
bool start_status_pdo_mapping ()
 Start definition of the status PDO mapping. More...
 
template<typename T >
bool add_status_pdo_mapping (uint16_t pdo_address)
 Add a new STATUS PDO map link. More...
 
template<typename T >
bool end_status_pdo_mapping ()
 Finish definition of the status PDO mapping. More...
 
void configure_dc_sync0 (uint32_t cycle_time_0, int32_t cycle_shift) const
 Define DC synchro signal 0. More...
 
void configure_dc_sync0_1 (uint32_t cycle_time_0, uint32_t cycle_time_1, int32_t cycle_shift) const
 Define DC synchro signals 0 and 1. More...
 
int32_t read_file (std::string_view filename, uint32_t password, int32_t size, uint8_t *buffer) const
 
bool write_file (std::string_view filename, uint32_t password, int32_t size, uint8_t *buffer) const
 
bool read_sercos (uint8_t drive, uint8_t flags, uint16_t idn, int32_t size, uint8_t *buffer) const
 
bool write_sercos (uint8_t drive, uint8_t flags, uint16_t idn, int32_t size, uint8_t *buffer) const
 
- Static Protected Attributes inherited from ethercatcpp::coe::cia402::CIA402Device
static const std::map< int8_t, std::string_view > std_control_mode_str
 

Detailed Description

This class describe the EtherCAT driver for Sensodrive sensojoint actuator. It allows to communicate with a "Sensodrive Sensojoint actuator" through an ethercat bus managed by an ethercatcpp master.

Member Typedef Documentation

◆ operation_state_t

using ethercatcpp::SensoJoint::operation_state_t = CIA402Device::state_t

Member Enumeration Documentation

◆ control_mode_t

This enum define the possible "control modes" of the actuator.

Enumerator
monitor 
profile_position 
profile_velocity 
profile_torque 
cyclic_position 
cyclic_velocity 
cyclic_torque 
profile_output_position_vibration_damping 
profile_output_velocity 
cyclic_output_position_vibration_damping 
cyclic_output_velocity 
cyclic_output_torque 

◆ IOFlag

Flag to ease setting the controlled/read GPIOS.

only 4 usable GPIOs in the sensojoint (=> only 4 first bits used in flags)

Enumerator
gpio_3_io_fpp_pin 
gpio_4_out_pin 
gpio_5_io_sbo_pin 
gpio_6_io_sbo_pin 

◆ Model

Enumerator
MODEL_7016 
MODEL_5016 
MODEL_4010 
MODEL_3010 

Constructor & Destructor Documentation

◆ SensoJoint() [1/4]

ethercatcpp::SensoJoint::SensoJoint ( const Model model)

Constructor of SensoJoint class.

◆ SensoJoint() [2/4]

ethercatcpp::SensoJoint::SensoJoint ( const Model model,
const Options options 
)

◆ SensoJoint() [3/4]

ethercatcpp::SensoJoint::SensoJoint ( const SensoJoint )
delete

◆ SensoJoint() [4/4]

ethercatcpp::SensoJoint::SensoJoint ( SensoJoint &&  )
delete

◆ ~SensoJoint()

virtual ethercatcpp::SensoJoint::~SensoJoint ( )
virtual

Member Function Documentation

◆ advanced_mode()

static bool ethercatcpp::SensoJoint::advanced_mode ( int8_t  )
staticprotected

◆ bind_buffers()

void ethercatcpp::SensoJoint::bind_buffers ( )
private

◆ brake_applied()

bool ethercatcpp::SensoJoint::brake_applied ( ) const

Tell whether Sensojoint brake is applied.

Returns
true if brake applied (joint cannot move), false otherwise

◆ can_swap_mode()

static bool ethercatcpp::SensoJoint::can_swap_mode ( control_mode_t  current,
control_mode_t  next 
)
staticprivate

◆ control_code_to_mode()

static control_mode_t ethercatcpp::SensoJoint::control_code_to_mode ( int8_t  )
staticprivate

◆ control_mode()

control_mode_t ethercatcpp::SensoJoint::control_mode ( ) const

Get current control mode used inside device.

Returns
the current control mode

◆ control_mode_str()

std::string_view ethercatcpp::SensoJoint::control_mode_str ( ) const

Get current control mode used inside device as a string.

Returns
explicit actual control mode like in "control_mode_t"

◆ control_mode_to_code()

static int8_t ethercatcpp::SensoJoint::control_mode_to_code ( control_mode_t  )
staticprivate

◆ control_mode_to_str()

static std::string_view ethercatcpp::SensoJoint::control_mode_to_str ( control_mode_t  )
static

convert the operation state into a human readable information

Returns
std::string

◆ cyclic_mode() [1/2]

virtual bool ethercatcpp::SensoJoint::cyclic_mode ( ) const
overridevirtual

◆ cyclic_mode() [2/2]

static bool ethercatcpp::SensoJoint::cyclic_mode ( int8_t  )
staticprotected

◆ cyclic_mode_queried()

virtual bool ethercatcpp::SensoJoint::cyclic_mode_queried ( ) const
overridevirtual

◆ digital_inputs()

uint8_t ethercatcpp::SensoJoint::digital_inputs ( ) const

Get value of digital inputs.

only bits "0000 1101" are meaningfull, corresponding to GPIOs 3,5,6 (from rightmost to leftmost bit => 1101 == 6 5 _ 3)

you can use IOFlags to check status of corresponding inputs

Returns
digital inputs bitset value (1 for High, 0 for Low)

◆ drive_temperature()

double ethercatcpp::SensoJoint::drive_temperature ( ) const

Get actual drive temperature in degrees celsius (°C).

Returns
drive current temperature

◆ error_code()

uint16_t ethercatcpp::SensoJoint::error_code ( ) const

Get last error code.

See also
fault()

◆ fault()

const std::string& ethercatcpp::SensoJoint::fault ( ) const

Get last fault description.

Returns
the string explaining the fault
See also
fault_type()

◆ find_initial_position()

void ethercatcpp::SensoJoint::find_initial_position ( )
private

◆ following_error()

bool ethercatcpp::SensoJoint::following_error ( ) const

In profile modes tell whether there is a following error.

Returns
true if there is a following error false otherwise

◆ force_target_motor_torque()

void ethercatcpp::SensoJoint::force_target_motor_torque ( double  target_torque)
private

◆ force_target_output_torque()

void ethercatcpp::SensoJoint::force_target_output_torque ( double  target_torque)
private

◆ friction_torque()

double ethercatcpp::SensoJoint::friction_torque ( ) const

Get actual friction torque in newton meter (Nm).

Returns
torque value

◆ gen_options()

static SensoJoint::Options ethercatcpp::SensoJoint::gen_options ( double  control_period,
double  min_target_pos,
double  max_target_pos 
)
static

◆ initial_position()

double ethercatcpp::SensoJoint::initial_position ( ) const

Get the theoric initial position from drive configuration.

Returns
the initial position

◆ initialize()

void ethercatcpp::SensoJoint::initialize ( const std::optional< Options > &  options)
private

◆ is_advanced_mode()

static bool ethercatcpp::SensoJoint::is_advanced_mode ( control_mode_t  )
static

◆ is_cyclic_mode()

static bool ethercatcpp::SensoJoint::is_cyclic_mode ( control_mode_t  )
static

◆ is_position_mode()

static bool ethercatcpp::SensoJoint::is_position_mode ( control_mode_t  )
static

◆ is_profile_mode()

static bool ethercatcpp::SensoJoint::is_profile_mode ( control_mode_t  )
static

◆ is_torque_mode()

static bool ethercatcpp::SensoJoint::is_torque_mode ( control_mode_t  )
static

◆ is_velocity_mode()

static bool ethercatcpp::SensoJoint::is_velocity_mode ( control_mode_t  )
static

◆ manage_control_period()

void ethercatcpp::SensoJoint::manage_control_period ( const std::optional< Options > &  options)
private

◆ manage_ctrl_params()

void ethercatcpp::SensoJoint::manage_ctrl_params ( const std::optional< Options > &  options)
private

◆ manage_digital_ios()

void ethercatcpp::SensoJoint::manage_digital_ios ( const std::optional< Options > &  options)
private

◆ manage_digital_ios_end()

void ethercatcpp::SensoJoint::manage_digital_ios_end ( )
private

◆ manage_endstop_config()

void ethercatcpp::SensoJoint::manage_endstop_config ( const std::optional< Options > &  options)
private

◆ manage_max_motor_current()

void ethercatcpp::SensoJoint::manage_max_motor_current ( )
private

◆ manage_max_motor_torque()

void ethercatcpp::SensoJoint::manage_max_motor_torque ( )
private

◆ manage_max_motor_velocity()

void ethercatcpp::SensoJoint::manage_max_motor_velocity ( )
private

◆ manage_max_output_torque()

void ethercatcpp::SensoJoint::manage_max_output_torque ( )
private

◆ manage_max_output_velocity()

void ethercatcpp::SensoJoint::manage_max_output_velocity ( )
private

◆ manage_position_offset()

void ethercatcpp::SensoJoint::manage_position_offset ( const std::optional< Options > &  options)
private

◆ manage_profile_config()

void ethercatcpp::SensoJoint::manage_profile_config ( const std::optional< Options > &  options)
private

◆ manage_quickstop_config()

void ethercatcpp::SensoJoint::manage_quickstop_config ( const std::optional< Options > &  options)
private

◆ manage_torque_based_quick_stop()

void ethercatcpp::SensoJoint::manage_torque_based_quick_stop ( )
private

◆ manage_torque_offset()

void ethercatcpp::SensoJoint::manage_torque_offset ( const std::optional< Options > &  options)
private

◆ manage_torque_slope()

void ethercatcpp::SensoJoint::manage_torque_slope ( const std::optional< Options > &  options)
private

◆ manage_user_max_motor_torque()

void ethercatcpp::SensoJoint::manage_user_max_motor_torque ( const std::optional< Options > &  options)
private

◆ manage_user_max_motor_velocity()

void ethercatcpp::SensoJoint::manage_user_max_motor_velocity ( const std::optional< Options > &  options)
private

◆ manage_user_position_limits()

void ethercatcpp::SensoJoint::manage_user_position_limits ( const std::optional< Options > &  options)
private

◆ motor_current()

double ethercatcpp::SensoJoint::motor_current ( ) const

Get actual motor current in A.

Returns
motor current value

◆ motor_temperature()

double ethercatcpp::SensoJoint::motor_temperature ( ) const

Get actual motor temperature in degrees celsius (°C).

Returns
motor current temperature

◆ motor_torque()

double ethercatcpp::SensoJoint::motor_torque ( ) const

Get actual motor torque in newton meter.

Returns
torque value

◆ operator=() [1/2]

SensoJoint& ethercatcpp::SensoJoint::operator= ( const SensoJoint )
delete

◆ operator=() [2/2]

SensoJoint& ethercatcpp::SensoJoint::operator= ( SensoJoint &&  )
delete

◆ options()

const Options& ethercatcpp::SensoJoint::options ( ) const

Get options used in the Sensojoint.

Returns
reference on the option object

◆ output_torque()

double ethercatcpp::SensoJoint::output_torque ( ) const

Get actual output torque in newton meter (Nm).

Returns
torque value

◆ pdo_maps_configuration()

void ethercatcpp::SensoJoint::pdo_maps_configuration ( )
private

◆ position()

double ethercatcpp::SensoJoint::position ( ) const

Get actual motor position in radians.

Returns
position value

◆ position_mode() [1/2]

virtual bool ethercatcpp::SensoJoint::position_mode ( ) const
overridevirtual

◆ position_mode() [2/2]

static bool ethercatcpp::SensoJoint::position_mode ( int8_t  )
staticprotected

◆ position_mode_queried()

virtual bool ethercatcpp::SensoJoint::position_mode_queried ( ) const
overridevirtual

◆ profile_mode() [1/2]

virtual bool ethercatcpp::SensoJoint::profile_mode ( ) const
overridevirtual

◆ profile_mode() [2/2]

static bool ethercatcpp::SensoJoint::profile_mode ( int8_t  )
staticprotected

◆ profile_mode_queried()

virtual bool ethercatcpp::SensoJoint::profile_mode_queried ( ) const
overridevirtual

◆ read_base_units_values()

void ethercatcpp::SensoJoint::read_base_units_values ( )
private

◆ sbc_active()

bool ethercatcpp::SensoJoint::sbc_active ( ) const

Check whether SBC(Safe braque control) security has been triggerred.

Returns
TRUE when SBC triggerred, FALSE otherwise

◆ sensor_temperature()

double ethercatcpp::SensoJoint::sensor_temperature ( ) const

Get actual torque sensor temperature in degrees celsius (°C).

Returns
torque sensor current temperature

◆ set_control_mode()

bool ethercatcpp::SensoJoint::set_control_mode ( control_mode_t  control_mode)

Select the desired control mode.

Parameters
[in]control_modeis the desired control mode
Returns
true if mode has changed, false otherwise

◆ set_digital_outputs()

void ethercatcpp::SensoJoint::set_digital_outputs ( uint8_t  outputs)

Set value of digital outputs.

only 4 first bits (0000 1111) are used, corresponding to GPIOs 3,4,5,6 (from rightmost to leftmost bit => 1111 == 6 5 4 3)

you can use IOFlags to set the output values

Parameters
outputsbitset value of digital outputs (1 for High, 0 for Low)

◆ set_external_load_torque_offset()

void ethercatcpp::SensoJoint::set_external_load_torque_offset ( double  offset)

Set value of external load torque offset (gravity)

Parameters
offsetadditional torque due to gravity (to be compensated)

◆ set_motor_torque_feedforward()

void ethercatcpp::SensoJoint::set_motor_torque_feedforward ( double  torque_offset)

Function used to set the motor torque offset.

Set the torque feedforward offset for the torque value. In Cyclic Synchronous Position Mode and Cyclic Synchronous Velocity Mode, the object contains the input value for torque feed forward. In Cyclic Synchronous Torque Mode, it contains the commanded additive torque of the drive, which is added to the Target Torque value. unit: Newton meter (Nm) .

Parameters
[in]torque_offsetis the torque offset desired

◆ set_output_torque_feedforward()

void ethercatcpp::SensoJoint::set_output_torque_feedforward ( double  torque_offset)

Function used to set the output torque offset.

Same as set_motor_torque_feedforward but the input is expressed in desired output torque and converted to desired motor torque

Parameters
[in]torque_offsetis the desired output torque offset
See also
set_motor_torque_feedforward

◆ set_spring()

void ethercatcpp::SensoJoint::set_spring ( double  neutral_position,
double  stiffness,
double  damping 
)

Set value of spring haptics effect parameters in advanced torque controller.

Parameters
neutral_positionof spring
stiffnessof spring
dampingof spring

◆ set_target_motor_torque()

void ethercatcpp::SensoJoint::set_target_motor_torque ( double  target_torque)

Function used to set the target motor torque when device is command in basic torque mode.

unit: Newton meter (Nm).

Parameters
[in]target_torqueis the torque desired

◆ set_target_output_torque()

void ethercatcpp::SensoJoint::set_target_output_torque ( double  target_torque)

Function used to set the target torque on output shaft when device is command in output or basic torque modes.

unit: Newton meter (Nm).

Parameters
[in]target_torqueis the torque desired

◆ set_target_position()

void ethercatcpp::SensoJoint::set_target_position ( double  target_position)

Function used to set the target position when device is command in position mode.

unit: radian (rad).

Parameters
[in]target_positionis the position desired

◆ set_target_velocity()

void ethercatcpp::SensoJoint::set_target_velocity ( double  target_velocity)

Function used to set the target velocity when device is command in velocity mode.

unit: radian per second (rad/s) .

Parameters
[in]target_velocityis the velocity desired

◆ set_velocity_feedforward()

void ethercatcpp::SensoJoint::set_velocity_feedforward ( double  velocity_offset)

Function used to set the velocity offset.

Provides the feedforward offset of the velocity value. In Cyclic Synchronous Position Mode, this object contains the input value for velocity feed forward. In Cyclic Synchronous Velocity Mode, it contains the commanded offset of the drive device. unit: radian (rad per second).

Parameters
[in]velocity_offsetis the velocity offset desired

◆ standstill()

bool ethercatcpp::SensoJoint::standstill ( ) const

In profile velocity modes tell whether the motor is standstill.

Returns
true if standstill false otherwise

◆ sto_active()

bool ethercatcpp::SensoJoint::sto_active ( ) const

Check whether STO(Safe torque off) security has been triggerred.

Returns
TRUE when STO triggerred, FALSE otherwise

◆ torque_mode() [1/2]

virtual bool ethercatcpp::SensoJoint::torque_mode ( ) const
overridevirtual

◆ torque_mode() [2/2]

static bool ethercatcpp::SensoJoint::torque_mode ( int8_t  )
staticprotected

◆ torque_mode_queried()

virtual bool ethercatcpp::SensoJoint::torque_mode_queried ( ) const
overridevirtual

◆ unpack_status_buffer()

void ethercatcpp::SensoJoint::unpack_status_buffer ( )
private

◆ update_internal_state()

void ethercatcpp::SensoJoint::update_internal_state ( )
private

◆ velocity()

double ethercatcpp::SensoJoint::velocity ( ) const

Get actual motor velocity in radians per second.

Returns
velocity value

◆ velocity_mode() [1/2]

virtual bool ethercatcpp::SensoJoint::velocity_mode ( ) const
overridevirtual

◆ velocity_mode() [2/2]

static bool ethercatcpp::SensoJoint::velocity_mode ( int8_t  )
staticprotected

◆ velocity_mode_queried()

virtual bool ethercatcpp::SensoJoint::velocity_mode_queried ( ) const
overridevirtual

◆ warning()

bool ethercatcpp::SensoJoint::warning ( ) const

check if a warning is currently emitted.

See also
fault()

Member Data Documentation

◆ control_mode_decode_

const std::map<int8_t, std::string_view> ethercatcpp::SensoJoint::control_mode_decode_
staticprivate

◆ conversion_

std::unique_ptr<ConversionRatios> ethercatcpp::SensoJoint::conversion_
private

◆ internal_parameters_

std::unique_ptr<InternalParameters> ethercatcpp::SensoJoint::internal_parameters_
private

◆ model_

Model ethercatcpp::SensoJoint::model_
private

◆ options_

Options ethercatcpp::SensoJoint::options_
private

◆ sta_cmd_

std::unique_ptr<OpaqueStateCommands> ethercatcpp::SensoJoint::sta_cmd_
private

The documentation for this class was generated from the following file: