#include <tmc_coe_ros.h>
Definition at line 28 of file tmc_coe_ros.h.
◆ TmcCoeROS()
Copyright (c) 2023-2024 Analog Devices, Inc. All Rights Reserved. This software is proprietary to Analog Devices, Inc. and its licensors.
Definition at line 11 of file tmc_coe_ros.cpp.
◆ ~TmcCoeROS()
| TmcCoeROS::~TmcCoeROS |
( |
| ) |
|
◆ createMotor()
| void TmcCoeROS::createMotor |
( |
| ) |
|
|
private |
◆ cyclicSyncModeCallback()
| bool TmcCoeROS::cyclicSyncModeCallback |
( |
adi_tmc_coe::CSx_mode::Request & |
req, |
|
|
adi_tmc_coe::CSx_mode::Response & |
res |
|
) |
| |
|
private |
◆ deInit()
| void TmcCoeROS::deInit |
( |
| ) |
|
◆ enFlagsVectorParamCheck()
| uint8_t TmcCoeROS::enFlagsVectorParamCheck |
( |
std::string |
param_name, |
|
|
std::vector< int > & |
param_var, |
|
|
uint32_t |
max_val |
|
) |
| |
|
private |
◆ initialize()
| bool TmcCoeROS::initialize |
( |
| ) |
|
◆ initService()
| void TmcCoeROS::initService |
( |
| ) |
|
|
private |
◆ isInterfaceUnresponsive()
| bool TmcCoeROS::isInterfaceUnresponsive |
( |
| ) |
|
◆ readPDOCallBack()
| bool TmcCoeROS::readPDOCallBack |
( |
adi_tmc_coe::read_write_PDO::Request & |
req, |
|
|
adi_tmc_coe::read_write_PDO::Response & |
res |
|
) |
| |
|
private |
◆ readSDOCallBack()
| bool TmcCoeROS::readSDOCallBack |
( |
adi_tmc_coe::read_write_SDO::Request & |
req, |
|
|
adi_tmc_coe::read_write_SDO::Response & |
res |
|
) |
| |
|
private |
◆ stateChangeCallback()
| bool TmcCoeROS::stateChangeCallback |
( |
adi_tmc_coe::state_change::Request & |
req, |
|
|
adi_tmc_coe::state_change::Response & |
res |
|
) |
| |
|
private |
◆ validateAutogenParams()
| bool TmcCoeROS::validateAutogenParams |
( |
| ) |
|
|
private |
◆ validateInterfaceParams()
| bool TmcCoeROS::validateInterfaceParams |
( |
| ) |
|
|
private |
◆ writePDOCallBack()
| bool TmcCoeROS::writePDOCallBack |
( |
adi_tmc_coe::read_write_PDO::Request & |
req, |
|
|
adi_tmc_coe::read_write_PDO::Response & |
res |
|
) |
| |
|
private |
◆ writeSDOCallBack()
| bool TmcCoeROS::writeSDOCallBack |
( |
adi_tmc_coe::read_write_SDO::Request & |
req, |
|
|
adi_tmc_coe::read_write_SDO::Response & |
res |
|
) |
| |
|
private |
◆ cyclic_sync_server_
◆ p_motor_
| std::vector<std::vector<TmcCoeMotor*> > TmcCoeROS::p_motor_ |
|
private |
◆ p_nh_
◆ p_tmc_coe_interpreter_
◆ param_adhoc_mode_
| std::vector<int> TmcCoeROS::param_adhoc_mode_ |
|
private |
◆ param_en_motor_
| std::vector<int> TmcCoeROS::param_en_motor_ |
|
private |
◆ param_en_slave_
| std::vector<int> TmcCoeROS::param_en_slave_ |
|
private |
◆ param_interface_name_
| std::string TmcCoeROS::param_interface_name_ |
|
private |
◆ param_interface_timeout_
| double TmcCoeROS::param_interface_timeout_ |
|
private |
◆ param_SDO_PDO_retries_
| int TmcCoeROS::param_SDO_PDO_retries_ |
|
private |
◆ read_pdo_server_
◆ read_sdo_server_
◆ s_namespace_
| std::string TmcCoeROS::s_namespace_ |
|
private |
◆ s_node_name_
| std::string TmcCoeROS::s_node_name_ |
|
private |
◆ slave_name_str_
| std::vector<std::string> TmcCoeROS::slave_name_str_ |
|
private |
◆ state_change_server_
◆ total_motor_vector_
| std::vector<uint8_t> TmcCoeROS::total_motor_vector_ |
|
private |
◆ total_slaves_
◆ write_pdo_server_
◆ write_sdo_server_
The documentation for this class was generated from the following files: