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

#include <tmc_coe_ros.h>

Public Member Functions

void deInit ()
 
bool initialize ()
 
bool isInterfaceUnresponsive ()
 
 TmcCoeROS (ros::NodeHandle *p_nh)
 
 ~TmcCoeROS ()
 

Private Member Functions

void createMotor ()
 
bool cyclicSyncModeCallback (adi_tmc_coe::CSx_mode::Request &req, adi_tmc_coe::CSx_mode::Response &res)
 
uint8_t enFlagsVectorParamCheck (std::string param_name, std::vector< int > &param_var, uint32_t max_val)
 
void initService ()
 
bool readPDOCallBack (adi_tmc_coe::read_write_PDO::Request &req, adi_tmc_coe::read_write_PDO::Response &res)
 
bool readSDOCallBack (adi_tmc_coe::read_write_SDO::Request &req, adi_tmc_coe::read_write_SDO::Response &res)
 
bool stateChangeCallback (adi_tmc_coe::state_change::Request &req, adi_tmc_coe::state_change::Response &res)
 
bool validateAutogenParams ()
 
bool validateInterfaceParams ()
 
bool writePDOCallBack (adi_tmc_coe::read_write_PDO::Request &req, adi_tmc_coe::read_write_PDO::Response &res)
 
bool writeSDOCallBack (adi_tmc_coe::read_write_SDO::Request &req, adi_tmc_coe::read_write_SDO::Response &res)
 

Private Attributes

ros::ServiceServer cyclic_sync_server_
 
std::vector< std::vector< TmcCoeMotor * > > p_motor_
 
ros::NodeHandlep_nh_
 
TmcCoeInterpreterp_tmc_coe_interpreter_
 
std::vector< int > param_adhoc_mode_
 
std::vector< int > param_en_motor_
 
std::vector< int > param_en_slave_
 
std::string param_interface_name_
 
double param_interface_timeout_
 
int param_SDO_PDO_retries_
 
ros::ServiceServer read_pdo_server_
 
ros::ServiceServer read_sdo_server_
 
std::string s_namespace_
 
std::string s_node_name_
 
std::vector< std::string > slave_name_str_
 
ros::ServiceServer state_change_server_
 
std::vector< uint8_ttotal_motor_vector_
 
uint8_t total_slaves_
 
ros::ServiceServer write_pdo_server_
 
ros::ServiceServer write_sdo_server_
 

Detailed Description

Definition at line 28 of file tmc_coe_ros.h.

Constructor & Destructor Documentation

◆ TmcCoeROS()

TmcCoeROS::TmcCoeROS ( ros::NodeHandle p_nh)

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

Definition at line 20 of file tmc_coe_ros.cpp.

Member Function Documentation

◆ createMotor()

void TmcCoeROS::createMotor ( )
private

Definition at line 270 of file tmc_coe_ros.cpp.

◆ cyclicSyncModeCallback()

bool TmcCoeROS::cyclicSyncModeCallback ( adi_tmc_coe::CSx_mode::Request &  req,
adi_tmc_coe::CSx_mode::Response &  res 
)
private

Definition at line 806 of file tmc_coe_ros.cpp.

◆ deInit()

void TmcCoeROS::deInit ( )

Definition at line 400 of file tmc_coe_ros.cpp.

◆ enFlagsVectorParamCheck()

uint8_t TmcCoeROS::enFlagsVectorParamCheck ( std::string  param_name,
std::vector< int > &  param_var,
uint32_t  max_val 
)
private

Definition at line 342 of file tmc_coe_ros.cpp.

◆ initialize()

bool TmcCoeROS::initialize ( )

Definition at line 47 of file tmc_coe_ros.cpp.

◆ initService()

void TmcCoeROS::initService ( )
private

Definition at line 422 of file tmc_coe_ros.cpp.

◆ isInterfaceUnresponsive()

bool TmcCoeROS::isInterfaceUnresponsive ( )

Definition at line 407 of file tmc_coe_ros.cpp.

◆ readPDOCallBack()

bool TmcCoeROS::readPDOCallBack ( adi_tmc_coe::read_write_PDO::Request &  req,
adi_tmc_coe::read_write_PDO::Response &  res 
)
private

Definition at line 664 of file tmc_coe_ros.cpp.

◆ readSDOCallBack()

bool TmcCoeROS::readSDOCallBack ( adi_tmc_coe::read_write_SDO::Request &  req,
adi_tmc_coe::read_write_SDO::Response &  res 
)
private

Definition at line 503 of file tmc_coe_ros.cpp.

◆ stateChangeCallback()

bool TmcCoeROS::stateChangeCallback ( adi_tmc_coe::state_change::Request &  req,
adi_tmc_coe::state_change::Response &  res 
)
private

Definition at line 726 of file tmc_coe_ros.cpp.

◆ validateAutogenParams()

bool TmcCoeROS::validateAutogenParams ( )
private

Definition at line 189 of file tmc_coe_ros.cpp.

◆ validateInterfaceParams()

bool TmcCoeROS::validateInterfaceParams ( )
private

Definition at line 133 of file tmc_coe_ros.cpp.

◆ writePDOCallBack()

bool TmcCoeROS::writePDOCallBack ( adi_tmc_coe::read_write_PDO::Request &  req,
adi_tmc_coe::read_write_PDO::Response &  res 
)
private

Definition at line 560 of file tmc_coe_ros.cpp.

◆ writeSDOCallBack()

bool TmcCoeROS::writeSDOCallBack ( adi_tmc_coe::read_write_SDO::Request &  req,
adi_tmc_coe::read_write_SDO::Response &  res 
)
private

Definition at line 532 of file tmc_coe_ros.cpp.

Member Data Documentation

◆ cyclic_sync_server_

ros::ServiceServer TmcCoeROS::cyclic_sync_server_
private

Definition at line 49 of file tmc_coe_ros.h.

◆ p_motor_

std::vector<std::vector<TmcCoeMotor*> > TmcCoeROS::p_motor_
private

Definition at line 65 of file tmc_coe_ros.h.

◆ p_nh_

ros::NodeHandle* TmcCoeROS::p_nh_
private

Definition at line 63 of file tmc_coe_ros.h.

◆ p_tmc_coe_interpreter_

TmcCoeInterpreter* TmcCoeROS::p_tmc_coe_interpreter_
private

Definition at line 64 of file tmc_coe_ros.h.

◆ param_adhoc_mode_

std::vector<int> TmcCoeROS::param_adhoc_mode_
private

Definition at line 58 of file tmc_coe_ros.h.

◆ param_en_motor_

std::vector<int> TmcCoeROS::param_en_motor_
private

Definition at line 59 of file tmc_coe_ros.h.

◆ param_en_slave_

std::vector<int> TmcCoeROS::param_en_slave_
private

Definition at line 57 of file tmc_coe_ros.h.

◆ param_interface_name_

std::string TmcCoeROS::param_interface_name_
private

Definition at line 54 of file tmc_coe_ros.h.

◆ param_interface_timeout_

double TmcCoeROS::param_interface_timeout_
private

Definition at line 56 of file tmc_coe_ros.h.

◆ param_SDO_PDO_retries_

int TmcCoeROS::param_SDO_PDO_retries_
private

Definition at line 55 of file tmc_coe_ros.h.

◆ read_pdo_server_

ros::ServiceServer TmcCoeROS::read_pdo_server_
private

Definition at line 43 of file tmc_coe_ros.h.

◆ read_sdo_server_

ros::ServiceServer TmcCoeROS::read_sdo_server_
private

Definition at line 39 of file tmc_coe_ros.h.

◆ s_namespace_

std::string TmcCoeROS::s_namespace_
private

Definition at line 53 of file tmc_coe_ros.h.

◆ s_node_name_

std::string TmcCoeROS::s_node_name_
private

Definition at line 52 of file tmc_coe_ros.h.

◆ slave_name_str_

std::vector<std::string> TmcCoeROS::slave_name_str_
private

Definition at line 61 of file tmc_coe_ros.h.

◆ state_change_server_

ros::ServiceServer TmcCoeROS::state_change_server_
private

Definition at line 47 of file tmc_coe_ros.h.

◆ total_motor_vector_

std::vector<uint8_t> TmcCoeROS::total_motor_vector_
private

Definition at line 60 of file tmc_coe_ros.h.

◆ total_slaves_

uint8_t TmcCoeROS::total_slaves_
private

Definition at line 51 of file tmc_coe_ros.h.

◆ write_pdo_server_

ros::ServiceServer TmcCoeROS::write_pdo_server_
private

Definition at line 45 of file tmc_coe_ros.h.

◆ write_sdo_server_

ros::ServiceServer TmcCoeROS::write_sdo_server_
private

Definition at line 41 of file tmc_coe_ros.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