tmc_coe_motor.h
Go to the documentation of this file.
1 
6 #ifndef TMC_COE_MOTOR_H
7 #define TMC_COE_MOTOR_H
8 
9 #include "tmc_coe_interpreter.h"
10 #include "adi_tmc_coe/TmcCoeInfo.h"
11 #include "geometry_msgs/Twist.h"
12 #include "std_msgs/Int32.h"
13 #include "std_msgs/String.h"
14 
15 /* Available Modes of Operation */
16 typedef enum
17 {
18  NONE = 0,
26 
27 /* Controlword command for different Position Control */
28 typedef enum
29 {
33 
34 const uint8_t DEFAULT_RATE = 10; //the Minimum rate is also the default rate
35 const uint8_t MAX_RATE = 100;
36 const uint8_t BLDC_MOTOR = 6;
37 
38 /* Conversion constants */
39 
40 /* Derived from converting linear velocity (ROS velocity unit) to rpm (TMC board velocity unit) */
41 const double PI = 3.1415926535;
42 const uint8_t SECS_TO_MIN = 60;
43 
44 /* Used for converting degrees (general position/angular unit) to steps (TMC board position/angular unit) */
46 
48 {
49 private:
50  void initParams();
51 
52 protected:
53  /* Publisher */
54  void initPublisher();
55  virtual void rosPublishTmcCoeInfo(const ros::TimerEvent& event);
58  adi_tmc_coe::TmcCoeInfo tmc_coe_info_msg_;
59  std::string frame_id_;
61 
62  /* Subscriber */
63  virtual void initSubscriber();
64  virtual void cmdVelCallback(const geometry_msgs::Twist& msg);
65  virtual void cmdAbsPosCallback(const std_msgs::Int32 msg);
66  virtual void cmdRelPosCallback(const std_msgs::Int32 msg);
70 
71  std::string s_node_name_;
72  std::string s_namespace_;
89  std::string param_interface_name_;
91 
94 
95 public:
96  TmcCoeMotor(ros::NodeHandle *p_nh, TmcCoeInterpreter* p_tmc_coe_interpreter,
97  uint8_t slave_number, uint8_t motor_number);
98  virtual ~TmcCoeMotor();
99  virtual void init();
100 };
101 
102 #endif /* TMC_COE_MOTOR_H */
TmcCoeMotor::s_node_name_
std::string s_node_name_
Definition: tmc_coe_motor.h:71
uint8_t
unsigned char uint8_t
TmcCoeMotor::slave_number_
uint8_t slave_number_
Definition: tmc_coe_motor.h:74
PI
const double PI
Definition: tmc_coe_motor.h:41
TmcCoeMotor::tmc_coe_info_msg_
adi_tmc_coe::TmcCoeInfo tmc_coe_info_msg_
Definition: tmc_coe_motor.h:58
ros::Publisher
PROFILE_VELOCITY
@ PROFILE_VELOCITY
Definition: tmc_coe_motor.h:20
MAX_RATE
const uint8_t MAX_RATE
Definition: tmc_coe_motor.h:35
uint16_t
unsigned short uint16_t
PROFILE_POSITION
@ PROFILE_POSITION
Definition: tmc_coe_motor.h:19
TmcCoeMotor::init
virtual void init()
Definition: tmc_coe_motor.cpp:33
TmcCoeMotor::param_interface_name_
std::string param_interface_name_
Definition: tmc_coe_motor.h:89
TmcCoeMotor::param_pub_rate_tmc_coe_info_
float param_pub_rate_tmc_coe_info_
Definition: tmc_coe_motor.h:90
TmcCoeMotor::param_wheel_diameter_
float param_wheel_diameter_
Definition: tmc_coe_motor.h:85
ANGULAR_FULL_ROTATION
const uint16_t ANGULAR_FULL_ROTATION
Definition: tmc_coe_motor.h:45
SECS_TO_MIN
const uint8_t SECS_TO_MIN
Definition: tmc_coe_motor.h:42
TmcCoeMotor::s_namespace_
std::string s_namespace_
Definition: tmc_coe_motor.h:72
TmcCoeMotor::param_add_ratio_pos_
float param_add_ratio_pos_
Definition: tmc_coe_motor.h:87
TmcCoeMotor::tmc_cmd_relpos_sub_
ros::Subscriber tmc_cmd_relpos_sub_
Definition: tmc_coe_motor.h:69
TmcCoeMotor::cmdAbsPosCallback
virtual void cmdAbsPosCallback(const std_msgs::Int32 msg)
Definition: tmc_coe_motor.cpp:383
TmcCoeMotor::TmcCoeMotor
TmcCoeMotor(ros::NodeHandle *p_nh, TmcCoeInterpreter *p_tmc_coe_interpreter, uint8_t slave_number, uint8_t motor_number)
Definition: tmc_coe_motor.cpp:11
TmcCoeMotor::param_SDO_PDO_retries_
int param_SDO_PDO_retries_
Definition: tmc_coe_motor.h:75
TmcCoeMotor::param_en_pub_tmc_coe_info_
bool param_en_pub_tmc_coe_info_
Definition: tmc_coe_motor.h:76
TmcCoeMotor::param_add_ratio_trq_
float param_add_ratio_trq_
Definition: tmc_coe_motor.h:88
TmcCoeMotor::rosPublishTmcCoeInfo
virtual void rosPublishTmcCoeInfo(const ros::TimerEvent &event)
Definition: tmc_coe_motor.cpp:276
TmcCoeMotor::param_tmc_coe_info_topic_
std::string param_tmc_coe_info_topic_
Definition: tmc_coe_motor.h:80
HOMING_MODE
@ HOMING_MODE
Definition: tmc_coe_motor.h:21
TmcCoeMotor::param_pub_actual_trq_
bool param_pub_actual_trq_
Definition: tmc_coe_motor.h:79
CYCLIC_SYNC_VEL
@ CYCLIC_SYNC_VEL
Definition: tmc_coe_motor.h:23
TmcCoeMotor::p_nh_
ros::NodeHandle * p_nh_
Definition: tmc_coe_motor.h:92
TmcCoeMotor::param_tmc_cmd_relpos_topic_
std::string param_tmc_cmd_relpos_topic_
Definition: tmc_coe_motor.h:83
TmcCoeMotor::param_tmc_cmd_abspos_topic_
std::string param_tmc_cmd_abspos_topic_
Definition: tmc_coe_motor.h:82
TmcCoeMotor::tmc_cmd_abspos_sub_
ros::Subscriber tmc_cmd_abspos_sub_
Definition: tmc_coe_motor.h:68
mode_of_operation_t
mode_of_operation_t
Definition: tmc_coe_motor.h:16
BLDC_MOTOR
const uint8_t BLDC_MOTOR
Definition: tmc_coe_motor.h:36
uint32_t
unsigned int uint32_t
pos_control_word_t
pos_control_word_t
Definition: tmc_coe_motor.h:28
TmcCoeMotor::initSubscriber
virtual void initSubscriber()
Definition: tmc_coe_motor.cpp:329
TmcCoeMotor::seq_ctr_
uint32_t seq_ctr_
Definition: tmc_coe_motor.h:60
TmcCoeMotor::initPublisher
void initPublisher()
Definition: tmc_coe_motor.cpp:237
TmcCoeMotor::tmc_cmd_vel_sub_
ros::Subscriber tmc_cmd_vel_sub_
Definition: tmc_coe_motor.h:67
TmcCoeMotor::~TmcCoeMotor
virtual ~TmcCoeMotor()
Definition: tmc_coe_motor.cpp:24
TmcCoeMotor::initParams
void initParams()
Definition: tmc_coe_motor.cpp:47
TmcCoeMotor::param_tmc_cmd_vel_topic_
std::string param_tmc_cmd_vel_topic_
Definition: tmc_coe_motor.h:81
ros::TimerEvent
TmcCoeMotor::frame_id_
std::string frame_id_
Definition: tmc_coe_motor.h:59
CYCLIC_SYNC_POS
@ CYCLIC_SYNC_POS
Definition: tmc_coe_motor.h:22
TmcCoeMotor
Definition: tmc_coe_motor.h:47
RELATIVE_POSITION
@ RELATIVE_POSITION
Definition: tmc_coe_motor.h:31
TmcCoeMotor::tmc_coe_info_pub_
ros::Publisher tmc_coe_info_pub_
Definition: tmc_coe_motor.h:57
TmcCoeMotor::cmdVelCallback
virtual void cmdVelCallback(const geometry_msgs::Twist &msg)
Definition: tmc_coe_motor.cpp:339
ABSOLUTE_POSITION
@ ABSOLUTE_POSITION
Definition: tmc_coe_motor.h:30
TmcCoeInterpreter
Definition: tmc_coe_interpreter.h:148
DEFAULT_RATE
const uint8_t DEFAULT_RATE
Definition: tmc_coe_motor.h:34
NONE
@ NONE
Definition: tmc_coe_motor.h:18
TmcCoeMotor::p_tmc_coe_interpreter_
TmcCoeInterpreter * p_tmc_coe_interpreter_
Definition: tmc_coe_motor.h:93
TmcCoeMotor::param_add_ratio_vel_
float param_add_ratio_vel_
Definition: tmc_coe_motor.h:86
TmcCoeMotor::cmdRelPosCallback
virtual void cmdRelPosCallback(const std_msgs::Int32 msg)
Definition: tmc_coe_motor.cpp:436
TmcCoeMotor::param_pub_actual_pos_
bool param_pub_actual_pos_
Definition: tmc_coe_motor.h:78
CYCLIC_SYNC_TRQ
@ CYCLIC_SYNC_TRQ
Definition: tmc_coe_motor.h:24
TmcCoeMotor::motor_number_
uint8_t motor_number_
Definition: tmc_coe_motor.h:73
TmcCoeMotor::param_pub_actual_vel_
bool param_pub_actual_vel_
Definition: tmc_coe_motor.h:77
tmc_coe_interpreter.h
TmcCoeMotor::param_tmc_cmd_trq_topic_
std::string param_tmc_cmd_trq_topic_
Definition: tmc_coe_motor.h:84
ros::Timer
ros::NodeHandle
TmcCoeMotor::timer_callback_
ros::Timer timer_callback_
Definition: tmc_coe_motor.h:56
ros::Subscriber


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