tmc_coe_ros.h
Go to the documentation of this file.
1 
6 #ifndef TMC_COE_ROS_H
7 #define TMC_COE_ROS_H
8 
9 #include "tmc_coe_bldc_motor.h"
10 #include "tmc_coe_stepper_motor.h"
11 #include "adi_tmc_coe/CSx_mode.h"
12 #include "adi_tmc_coe/read_write_SDO.h"
13 #include "adi_tmc_coe/read_write_PDO.h"
14 #include "adi_tmc_coe/state_change.h"
15 
23 const uint8_t TIMEOUT_MIN = 3;
24 const uint8_t TIMEOUT_MAX = 5;
27 
28 class TmcCoeROS
29 {
30 private:
32  bool validateAutogenParams();
33  void createMotor();
34  uint8_t enFlagsVectorParamCheck(std::string param_name, std::vector<int> &param_var, uint32_t max_val);
35 
36  /* Services */
37  void initService();
38  bool readSDOCallBack(adi_tmc_coe::read_write_SDO::Request& req, adi_tmc_coe::read_write_SDO::Response& res);
40  bool writeSDOCallBack(adi_tmc_coe::read_write_SDO::Request& req, adi_tmc_coe::read_write_SDO::Response& res);
42  bool readPDOCallBack(adi_tmc_coe::read_write_PDO::Request& req, adi_tmc_coe::read_write_PDO::Response& res);
44  bool writePDOCallBack(adi_tmc_coe::read_write_PDO::Request& req, adi_tmc_coe::read_write_PDO::Response& res);
46  bool stateChangeCallback(adi_tmc_coe::state_change::Request& req, adi_tmc_coe::state_change::Response& res);
48  bool cyclicSyncModeCallback(adi_tmc_coe::CSx_mode::Request& req, adi_tmc_coe::CSx_mode::Response& res);
50 
52  std::string s_node_name_;
53  std::string s_namespace_;
54  std::string param_interface_name_;
57  std::vector<int> param_en_slave_;
58  std::vector<int> param_adhoc_mode_;
59  std::vector<int> param_en_motor_;
60  std::vector<uint8_t> total_motor_vector_;
61  std::vector<std::string> slave_name_str_;
62 
65  std::vector<std::vector<TmcCoeMotor*>> p_motor_;
66 
67 public:
69  ~TmcCoeROS();
70  bool initialize();
71  void deInit();
73 };
74 
75 #endif /* TMC_COE_ROS_H */
uint8_t
unsigned char uint8_t
TIMEOUT_MAX
const uint8_t TIMEOUT_MAX
Definition: tmc_coe_ros.h:24
int8_t
signed char int8_t
TmcCoeROS::read_pdo_server_
ros::ServiceServer read_pdo_server_
Definition: tmc_coe_ros.h:43
TmcCoeROS::p_motor_
std::vector< std::vector< TmcCoeMotor * > > p_motor_
Definition: tmc_coe_ros.h:65
TmcCoeROS::s_namespace_
std::string s_namespace_
Definition: tmc_coe_ros.h:53
TmcCoeROS::readSDOCallBack
bool readSDOCallBack(adi_tmc_coe::read_write_SDO::Request &req, adi_tmc_coe::read_write_SDO::Response &res)
Definition: tmc_coe_ros.cpp:503
TmcCoeROS::param_interface_timeout_
double param_interface_timeout_
Definition: tmc_coe_ros.h:56
TmcCoeROS::stateChangeCallback
bool stateChangeCallback(adi_tmc_coe::state_change::Request &req, adi_tmc_coe::state_change::Response &res)
Definition: tmc_coe_ros.cpp:726
TmcCoeROS::param_en_motor_
std::vector< int > param_en_motor_
Definition: tmc_coe_ros.h:59
TmcCoeROS::TmcCoeROS
TmcCoeROS(ros::NodeHandle *p_nh)
Definition: tmc_coe_ros.cpp:11
TmcCoeROS::cyclicSyncModeCallback
bool cyclicSyncModeCallback(adi_tmc_coe::CSx_mode::Request &req, adi_tmc_coe::CSx_mode::Response &res)
Definition: tmc_coe_ros.cpp:806
TmcCoeROS::param_interface_name_
std::string param_interface_name_
Definition: tmc_coe_ros.h:54
TmcCoeROS::validateInterfaceParams
bool validateInterfaceParams()
Definition: tmc_coe_ros.cpp:133
MOTOR_TYPE_STEPPER_MIN
const uint8_t MOTOR_TYPE_STEPPER_MIN
Definition: tmc_coe_ros.h:17
TmcCoeROS::p_tmc_coe_interpreter_
TmcCoeInterpreter * p_tmc_coe_interpreter_
Definition: tmc_coe_ros.h:64
MOTOR_TYPE_STEPPER_MAX
const uint8_t MOTOR_TYPE_STEPPER_MAX
Definition: tmc_coe_ros.h:18
MOTOR_TYPE_BLDC
const uint8_t MOTOR_TYPE_BLDC
Definition: tmc_coe_ros.h:16
TmcCoeROS::s_node_name_
std::string s_node_name_
Definition: tmc_coe_ros.h:52
TmcCoeROS
Definition: tmc_coe_ros.h:28
TmcCoeROS::initService
void initService()
Definition: tmc_coe_ros.cpp:422
TmcCoeROS::initialize
bool initialize()
Definition: tmc_coe_ros.cpp:47
ros::ServiceServer
TmcCoeROS::isInterfaceUnresponsive
bool isInterfaceUnresponsive()
Definition: tmc_coe_ros.cpp:407
TmcCoeROS::readPDOCallBack
bool readPDOCallBack(adi_tmc_coe::read_write_PDO::Request &req, adi_tmc_coe::read_write_PDO::Response &res)
Definition: tmc_coe_ros.cpp:664
TmcCoeROS::state_change_server_
ros::ServiceServer state_change_server_
Definition: tmc_coe_ros.h:47
uint32_t
unsigned int uint32_t
TmcCoeROS::write_pdo_server_
ros::ServiceServer write_pdo_server_
Definition: tmc_coe_ros.h:45
SDO_PDO_RETRIES_DEFAULT
const uint8_t SDO_PDO_RETRIES_DEFAULT
Definition: tmc_coe_ros.h:19
TmcCoeROS::~TmcCoeROS
~TmcCoeROS()
Definition: tmc_coe_ros.cpp:20
TmcCoeROS::slave_name_str_
std::vector< std::string > slave_name_str_
Definition: tmc_coe_ros.h:61
TmcCoeROS::writePDOCallBack
bool writePDOCallBack(adi_tmc_coe::read_write_PDO::Request &req, adi_tmc_coe::read_write_PDO::Response &res)
Definition: tmc_coe_ros.cpp:560
TIMEOUT_DEFAULT
const uint8_t TIMEOUT_DEFAULT
Definition: tmc_coe_ros.h:22
TmcCoeROS::createMotor
void createMotor()
Definition: tmc_coe_ros.cpp:270
TmcCoeROS::total_slaves_
uint8_t total_slaves_
Definition: tmc_coe_ros.h:51
TmcCoeROS::write_sdo_server_
ros::ServiceServer write_sdo_server_
Definition: tmc_coe_ros.h:41
TIMEOUT_MIN
const uint8_t TIMEOUT_MIN
Definition: tmc_coe_ros.h:23
TmcCoeROS::total_motor_vector_
std::vector< uint8_t > total_motor_vector_
Definition: tmc_coe_ros.h:60
TmcCoeROS::validateAutogenParams
bool validateAutogenParams()
Definition: tmc_coe_ros.cpp:189
INTERPOLATION_TIME_INDEX_MAX
const uint8_t INTERPOLATION_TIME_INDEX_MAX
Definition: tmc_coe_ros.h:26
SDO_PDO_RETRIES_MAX
const uint8_t SDO_PDO_RETRIES_MAX
Definition: tmc_coe_ros.h:21
TmcCoeROS::p_nh_
ros::NodeHandle * p_nh_
Definition: tmc_coe_ros.h:63
TmcCoeInterpreter
Definition: tmc_coe_interpreter.h:148
TmcCoeROS::deInit
void deInit()
Definition: tmc_coe_ros.cpp:400
TmcCoeROS::param_adhoc_mode_
std::vector< int > param_adhoc_mode_
Definition: tmc_coe_ros.h:58
INTERPOLATION_TIME_INDEX_MIN
const int8_t INTERPOLATION_TIME_INDEX_MIN
Definition: tmc_coe_ros.h:25
tmc_coe_stepper_motor.h
tmc_coe_bldc_motor.h
TmcCoeROS::read_sdo_server_
ros::ServiceServer read_sdo_server_
Definition: tmc_coe_ros.h:39
TmcCoeROS::param_en_slave_
std::vector< int > param_en_slave_
Definition: tmc_coe_ros.h:57
SDO_PDO_RETRIES_MIN
const uint8_t SDO_PDO_RETRIES_MIN
Definition: tmc_coe_ros.h:20
TmcCoeROS::writeSDOCallBack
bool writeSDOCallBack(adi_tmc_coe::read_write_SDO::Request &req, adi_tmc_coe::read_write_SDO::Response &res)
Definition: tmc_coe_ros.cpp:532
TmcCoeROS::cyclic_sync_server_
ros::ServiceServer cyclic_sync_server_
Definition: tmc_coe_ros.h:49
ros::NodeHandle
TmcCoeROS::enFlagsVectorParamCheck
uint8_t enFlagsVectorParamCheck(std::string param_name, std::vector< int > &param_var, uint32_t max_val)
Definition: tmc_coe_ros.cpp:342
TmcCoeROS::param_SDO_PDO_retries_
int param_SDO_PDO_retries_
Definition: tmc_coe_ros.h:55


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