Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
TmcCoeInterpreter Class Reference

#include <tmc_coe_interpreter.h>

Public Member Functions

bool commandCodingTransition (uint8_t slave_number)
 
uint8_t deviceStateChange (uint8_t slave_number, nmt_state_t state)
 
uint8_t getCycleCounter ()
 
std::string getSlaveName (uint8_t slave_number)
 
uint8_t initInterface (std::string ifname)
 
bool isCycleFinished ()
 
bool isInterfaceUnresponsive ()
 
bool OPstate ()
 
void paramTransfer (std::vector< std::vector< std::string >> all_obj_name, std::vector< std::vector< std::string >> all_index, std::vector< std::vector< std::string >> all_sub_index, std::vector< std::vector< std::string >> all_datatype)
 
bool readSDO (uint8_t slave_number, std::string object_name, std::string *value)
 
bool safeOPstate (std::vector< int > en_slave)
 
void startCycleCounter ()
 
bool statusWordState (uint8_t slave_number, fsa_state_t state)
 
void stopCycleCounter ()
 
void stopInterface ()
 
 TmcCoeInterpreter (uint8_t SDO_PDO_retries, double interface_timeout)
 
bool writeSDO (uint8_t slave_number, std::string object_name, std::string *value)
 
 ~TmcCoeInterpreter ()
 

Public Attributes

std::vector< input_pdo_t * > input_pdo_
 
nmt_state_t nmt_state_
 
std::vector< output_pdo_t * > output_pdo_
 

Private Member Functions

void errorCheck ()
 
void processData ()
 
template<typename T >
std::string readSDO (uint8_t slave_number, uint16_t index_number, uint16_t subindex_number, T value)
 
int8_t setControlWord (uint8_t slave_number, fsa_state_t response_SW, control_word_state_t requested_CW)
 
template<typename T >
std::string writeSDO (uint8_t slave_number, uint16_t index_number, uint16_t subindex_number, T value)
 

Private Attributes

std::vector< std::vector< std::string > > all_datatype_
 
std::vector< std::vector< std::string > > all_index_
 
std::vector< std::vector< std::string > > all_obj_name_
 
std::vector< std::vector< std::string > > all_sub_index_
 
bool b_cycle_finished_
 
bool b_exit_threads_
 
bool b_interface_unresponsive_
 
bool b_start_cycle_count_
 
uint8_t cycle_counter_
 
boost::thread error_check_thread_
 
double interface_timeout_
 
char IOmap [IOMAP_SIZE]
 
boost::thread processdata_thread_
 
uint8_t SDO_PDO_retries_
 
std::vector< int > slave_
 
int work_count_
 

Detailed Description

Definition at line 148 of file tmc_coe_interpreter.h.

Constructor & Destructor Documentation

◆ TmcCoeInterpreter()

TmcCoeInterpreter::TmcCoeInterpreter ( uint8_t  SDO_PDO_retries,
double  interface_timeout 
)

Copyright (c) 2023-2024 Analog Devices, Inc. All Rights Reserved. This software is proprietary to Analog Devices, Inc. and its licensors.

Definition at line 12 of file tmc_coe_interpreter.cpp.

◆ ~TmcCoeInterpreter()

TmcCoeInterpreter::~TmcCoeInterpreter ( )

Definition at line 31 of file tmc_coe_interpreter.cpp.

Member Function Documentation

◆ commandCodingTransition()

bool TmcCoeInterpreter::commandCodingTransition ( uint8_t  slave_number)

Command Coding Transition

Parameters
slave_number= slave_number to which command to set
Returns
true if status word is on OPERATION_ENABLED state

Definition at line 198 of file tmc_coe_interpreter.cpp.

◆ deviceStateChange()

uint8_t TmcCoeInterpreter::deviceStateChange ( uint8_t  slave_number,
nmt_state_t  state 
)

Change Device State

Parameters
slave_number= slave_number to which state to set
state= state to change
Returns
current state in integer

Definition at line 379 of file tmc_coe_interpreter.cpp.

◆ errorCheck()

void TmcCoeInterpreter::errorCheck ( )
private

Error checking and recovery

Definition at line 754 of file tmc_coe_interpreter.cpp.

◆ getCycleCounter()

uint8_t TmcCoeInterpreter::getCycleCounter ( )

Getter for cycle_counter_ that indicates how many the cycle has been finished

Returns
cycle_counter value

Definition at line 689 of file tmc_coe_interpreter.cpp.

◆ getSlaveName()

std::string TmcCoeInterpreter::getSlaveName ( uint8_t  slave_number)

Getter for Slave Name

Parameters
slave_number= slave_number to which name to get
Returns
slave name in string

Definition at line 658 of file tmc_coe_interpreter.cpp.

◆ initInterface()

uint8_t TmcCoeInterpreter::initInterface ( std::string  ifname)

Initialize Ethernet Interface

Parameters
ifname= Device name, ex. "eth0"
Returns
total slave count, if 0 = fail

Definition at line 61 of file tmc_coe_interpreter.cpp.

◆ isCycleFinished()

bool TmcCoeInterpreter::isCycleFinished ( )

Getter for b_cycle_finished_ flag that indicates if processdata cyle is finished

Returns
b_cycle_finished_ status

Definition at line 679 of file tmc_coe_interpreter.cpp.

◆ isInterfaceUnresponsive()

bool TmcCoeInterpreter::isInterfaceUnresponsive ( )

Getter for b_interface_unresponsive_ flag that indicates if the master received no frames from the slave

Returns
b_interface_unresponsive_ status

Definition at line 718 of file tmc_coe_interpreter.cpp.

◆ OPstate()

bool TmcCoeInterpreter::OPstate ( )

Set Device and StatusWord to Operational State

Parameters
en_slave= vector of slaves enabled
Returns
true if success, false if not

Definition at line 145 of file tmc_coe_interpreter.cpp.

◆ paramTransfer()

void TmcCoeInterpreter::paramTransfer ( std::vector< std::vector< std::string >>  all_obj_name,
std::vector< std::vector< std::string >>  all_index,
std::vector< std::vector< std::string >>  all_sub_index,
std::vector< std::vector< std::string >>  all_datatype 
)

Initialize Ethernet Interface

Parameters
2Dvector of all obj_name, index, sub-index, and datatype

Definition at line 44 of file tmc_coe_interpreter.cpp.

◆ processData()

void TmcCoeInterpreter::processData ( )
private

Cyclic processdata

Definition at line 727 of file tmc_coe_interpreter.cpp.

◆ readSDO() [1/2]

bool TmcCoeInterpreter::readSDO ( uint8_t  slave_number,
std::string  object_name,
std::string *  value 
)

Read to SDO [High Level]

Parameters
slave_number= slave_number to which command to set
object_name= Object Name to read
value= will return actual value
Returns
true if read succesful, false if not

Definition at line 481 of file tmc_coe_interpreter.cpp.

◆ readSDO() [2/2]

template<typename T >
std::string TmcCoeInterpreter::readSDO ( uint8_t  slave_number,
uint16_t  index_number,
uint16_t  subindex_number,
value 
)
private

Read to SDO [Low Level]

Parameters
slave_number= slave_number to which command to set
index_number= index to read
subindex_number= subindex to read
value= used to set datatype of the object
Returns
actual value in string, returns empty if failed

Definition at line 860 of file tmc_coe_interpreter.cpp.

◆ safeOPstate()

bool TmcCoeInterpreter::safeOPstate ( std::vector< int >  en_slave)

Set Device to Safe_Operational State, also creates Cyclic processdata

Parameters
en_slave= vector of slaves enabled
Returns
true if success, false if not

Definition at line 90 of file tmc_coe_interpreter.cpp.

◆ setControlWord()

int8_t TmcCoeInterpreter::setControlWord ( uint8_t  slave_number,
fsa_state_t  response_SW,
control_word_state_t  requested_CW 
)
private

Set Control World

Parameters
slave_number= slave_number to which command to set
response_SW= required Status Word response
requested_CW= requested Control Word
Returns
0 if Status Word does not recover from FAULT, -1 if timeout is activated, 1 if successful

Definition at line 289 of file tmc_coe_interpreter.cpp.

◆ startCycleCounter()

void TmcCoeInterpreter::startCycleCounter ( )

Starts the Cycle counter

Definition at line 698 of file tmc_coe_interpreter.cpp.

◆ statusWordState()

bool TmcCoeInterpreter::statusWordState ( uint8_t  slave_number,
fsa_state_t  state 
)

Set statusWord to requested status

Parameters
slave_number= slave_number to which status is set
status_= enum of available status
Returns
true if current status is equal to set status, false if not

Definition at line 355 of file tmc_coe_interpreter.cpp.

◆ stopCycleCounter()

void TmcCoeInterpreter::stopCycleCounter ( )

Stops the Cycle counter

Definition at line 707 of file tmc_coe_interpreter.cpp.

◆ stopInterface()

void TmcCoeInterpreter::stopInterface ( )

Proper stopping of Interface

Definition at line 253 of file tmc_coe_interpreter.cpp.

◆ writeSDO() [1/2]

bool TmcCoeInterpreter::writeSDO ( uint8_t  slave_number,
std::string  object_name,
std::string *  value 
)

Write to SDO [High Level]

Parameters
slave_number= slave_number to which command to set
object_name= Object Name to write
value= value to set if write and returns actual value after set
Returns
true if write succesful, false if not

Definition at line 569 of file tmc_coe_interpreter.cpp.

◆ writeSDO() [2/2]

template<typename T >
std::string TmcCoeInterpreter::writeSDO ( uint8_t  slave_number,
uint16_t  index_number,
uint16_t  subindex_number,
value 
)
private

Read / Write to SDO [Low Level]

Parameters
slave_number= slave_number to which command to set
index_number= index to read / write
subindex_number= subindex to read / write
value= value to set, will return value if set to read
Returns
actual value in string, returns empty if failed

Definition at line 899 of file tmc_coe_interpreter.cpp.

Member Data Documentation

◆ all_datatype_

std::vector<std::vector<std::string> > TmcCoeInterpreter::all_datatype_
private

Definition at line 166 of file tmc_coe_interpreter.h.

◆ all_index_

std::vector<std::vector<std::string> > TmcCoeInterpreter::all_index_
private

Definition at line 164 of file tmc_coe_interpreter.h.

◆ all_obj_name_

std::vector<std::vector<std::string> > TmcCoeInterpreter::all_obj_name_
private

Definition at line 163 of file tmc_coe_interpreter.h.

◆ all_sub_index_

std::vector<std::vector<std::string> > TmcCoeInterpreter::all_sub_index_
private

Definition at line 165 of file tmc_coe_interpreter.h.

◆ b_cycle_finished_

bool TmcCoeInterpreter::b_cycle_finished_
private

Definition at line 172 of file tmc_coe_interpreter.h.

◆ b_exit_threads_

bool TmcCoeInterpreter::b_exit_threads_
private

Definition at line 171 of file tmc_coe_interpreter.h.

◆ b_interface_unresponsive_

bool TmcCoeInterpreter::b_interface_unresponsive_
private

Definition at line 175 of file tmc_coe_interpreter.h.

◆ b_start_cycle_count_

bool TmcCoeInterpreter::b_start_cycle_count_
private

Definition at line 173 of file tmc_coe_interpreter.h.

◆ cycle_counter_

uint8_t TmcCoeInterpreter::cycle_counter_
private

Definition at line 174 of file tmc_coe_interpreter.h.

◆ error_check_thread_

boost::thread TmcCoeInterpreter::error_check_thread_
private

Definition at line 154 of file tmc_coe_interpreter.h.

◆ input_pdo_

std::vector<input_pdo_t*> TmcCoeInterpreter::input_pdo_

Definition at line 200 of file tmc_coe_interpreter.h.

◆ interface_timeout_

double TmcCoeInterpreter::interface_timeout_
private

Definition at line 169 of file tmc_coe_interpreter.h.

◆ IOmap

char TmcCoeInterpreter::IOmap[IOMAP_SIZE]
private

Definition at line 161 of file tmc_coe_interpreter.h.

◆ nmt_state_

nmt_state_t TmcCoeInterpreter::nmt_state_

Definition at line 202 of file tmc_coe_interpreter.h.

◆ output_pdo_

std::vector<output_pdo_t*> TmcCoeInterpreter::output_pdo_

Definition at line 201 of file tmc_coe_interpreter.h.

◆ processdata_thread_

boost::thread TmcCoeInterpreter::processdata_thread_
private

Definition at line 152 of file tmc_coe_interpreter.h.

◆ SDO_PDO_retries_

uint8_t TmcCoeInterpreter::SDO_PDO_retries_
private

Definition at line 168 of file tmc_coe_interpreter.h.

◆ slave_

std::vector<int> TmcCoeInterpreter::slave_
private

Definition at line 162 of file tmc_coe_interpreter.h.

◆ work_count_

int TmcCoeInterpreter::work_count_
private

Definition at line 170 of file tmc_coe_interpreter.h.


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


adi_tmc_coe
Author(s):
autogenerated on Sun Feb 2 2025 03:07:24