tmc_coe_bldc_motor.cpp
Go to the documentation of this file.
1 
6 #include "tmc_coe_bldc_motor.h"
7 
9 
10 /* Constructor */
12  uint8_t slave_number, uint8_t motor_number) :
13 TmcCoeMotor(p_nh, p_tmc_coe_interpreter, slave_number, motor_number)
14 {
15  ROS_DEBUG_STREAM("[TmcCoeBLDCMotor::" << __func__ << "] called");
16 }
17 
18 /* Destructor */
20 {
21  ROS_DEBUG_STREAM("[TmcCoeBLDCMotor::" << __func__ << "] called");
22 }
23 
25 
27 {
28  const std::string s_commutation_mode = "Drive settings - Commutation mode";
29  const std::string s_position_scaler = "Drive settings - Position Scaler";
30  const std::string s_encoder_steps = "ABN encoder settings - Steps";
31  std::string val = "";
32  position_scaler_ = 0;
33  encoder_steps_ = 0;
34 
35  ROS_INFO_STREAM("[TmcCoeBLDCMotor::" << __func__ << "] called");
36 
37  if(p_tmc_coe_interpreter_->readSDO(slave_number_, s_commutation_mode, &val))
38  {
39  commutation_mode_ = (bldc_comm_mode_t) std::stoi(val);
40  val = "";
41  }
42  else
43  {
45  ROS_ERROR_STREAM("[" << __func__ << "] Object Name for Commutation Mode is not Available");
46  }
47 
49  {
50  if(p_tmc_coe_interpreter_->readSDO(slave_number_, s_position_scaler, &val))
51  {
52  position_scaler_ = std::stoi(val);
53  val = "";
54  }
55  else
56  {
57  ROS_ERROR_STREAM("[" << __func__ << "] Object Name for Position Scaler not Available");
58  }
59  }
60 
62  {
63  ROS_WARN_STREAM("[" << __func__ << "] Checking Encoder Steps");
64 
65  if(p_tmc_coe_interpreter_->readSDO(slave_number_, s_encoder_steps, &val))
66  {
67  encoder_steps_ = std::stoi(val);
68  }
69  else
70  {
71  ROS_ERROR_STREAM("[" << __func__ << "] Object Name for Encoder Steps not Available");
72  }
73  }
74 
75  if(param_wheel_diameter_ == 0)
76  {
77  ROS_INFO_STREAM("[" << __func__ << "] Velocity unit: rpm");
78  }
79  else
80  {
81  ROS_INFO_STREAM("[" << __func__ << "] Velocity unit: m/s");
82  }
83 
84  if(position_scaler_ == 0 && encoder_steps_ == 0)
85  {
86  ROS_INFO_STREAM("[" << __func__ << "] Position unit: pulses");
87  }
88  else
89  {
90  ROS_INFO_STREAM("[" << __func__ << "] Position unit: angular degrees");
91  }
92 
93  ROS_INFO_STREAM("[" << __func__ << "] Torque unit: mA");
94 
95  initPublisher();
96  this->initSubscriber();
97 
98  ROS_INFO_STREAM("[" << __func__ << "] Motor" << static_cast<int>(motor_number_) << " Initialized!\n");
99 }
100 
101 /* Publisher Callback */
103 {
104  std::string mode_of_operation = "";
105 
106  tmc_coe_info_msg_.header.stamp = ros::Time::now();
107  tmc_coe_info_msg_.header.seq = seq_ctr_;
108  tmc_coe_info_msg_.header.frame_id = frame_id_;
109  tmc_coe_info_msg_.interface_name = param_interface_name_;
110  tmc_coe_info_msg_.slave_number = slave_number_;
111  tmc_coe_info_msg_.motor_number = motor_number_;
112 
113  /* Initialize messages to 0 first */
114  tmc_coe_info_msg_.velocity = 0;
115  tmc_coe_info_msg_.position = 0;
116  tmc_coe_info_msg_.torque = 0;
117 
118  switch (p_tmc_coe_interpreter_->input_pdo_[slave_number_]->modes_of_operation_display)
119  {
120  case NONE: mode_of_operation = "None"; break;
121  case PROFILE_POSITION: mode_of_operation = "Profile Position"; break;
122  case PROFILE_VELOCITY: mode_of_operation = "Profile Velocity"; break;
123  case HOMING_MODE: mode_of_operation = "Homing Mode"; break;
124  case CYCLIC_SYNC_POS: mode_of_operation = "Cyclic Synchronous Position Mode"; break;
125  case CYCLIC_SYNC_VEL: mode_of_operation = "Cyclic Synchronous Velocity Mode"; break;
126  case CYCLIC_SYNC_TRQ: mode_of_operation = "Cyclic Synchronous Torque Mode"; break;
127  default : mode_of_operation = "NONE"; break;
128  }
129  tmc_coe_info_msg_.mode_of_operation = mode_of_operation;
131 
133  {
134  tmc_coe_info_msg_.velocity = p_tmc_coe_interpreter_->input_pdo_[slave_number_]->velocity_actual_value;
135 
136  // Convert rpm to linear velocity
137  if(param_wheel_diameter_ == 0)
138  {
139  tmc_coe_info_msg_.velocity = p_tmc_coe_interpreter_->input_pdo_[slave_number_]->velocity_actual_value *
141  }
142  else
143  {
144  tmc_coe_info_msg_.velocity = p_tmc_coe_interpreter_->input_pdo_[slave_number_]->velocity_actual_value *
146  }
147  }
148 
150  {
151  tmc_coe_info_msg_.position = p_tmc_coe_interpreter_->input_pdo_[slave_number_]->position_actual_value;
152 
153  // Convert steps to degrees
154  if(position_scaler_ > 0)
155  {
156  tmc_coe_info_msg_.position = p_tmc_coe_interpreter_->input_pdo_[slave_number_]->position_actual_value *
158  }
159  else if(encoder_steps_ > 0)
160  {
161  tmc_coe_info_msg_.position = p_tmc_coe_interpreter_->input_pdo_[slave_number_]->position_actual_value *
163  }
164  else
165  {
166  tmc_coe_info_msg_.position = p_tmc_coe_interpreter_->input_pdo_[slave_number_]->position_actual_value *
168  }
169  }
170 
172  {
173  tmc_coe_info_msg_.torque = p_tmc_coe_interpreter_->input_pdo_[slave_number_]->torque_actual_value *
175  }
176 
178  seq_ctr_++;
179 }
180 
181 /* Initialize Subscriber */
183 {
184  ROS_INFO_STREAM("[TmcCoeBLDCMotor::" << __func__ << "] called");
185 
186  switch (commutation_mode_)
187  {
188  case BLDC_DISABLED_MOTOR:
189  ROS_INFO_STREAM("[" << __func__ << "] Commutation Mode : DISABLED");
190  break;
191 
192  case BLDC_OPENLOOP_MOTOR:
193  ROS_INFO_STREAM("[" << __func__ << "] Commutation Mode : OPEN LOOP");
195  break;
196 
197  default:
198  ROS_INFO_STREAM("[" << __func__ << "] Commutation Mode : CLOSED LOOP");
200  break;
201  }
202 }
203 
204 /* Subscriber Callback */
205 void TmcCoeBLDCMotor::cmdVelCallback(const geometry_msgs::Twist& msg)
206 {
207  float val = msg.linear.x;
208  int32_t board_val = 0;
209  uint8_t prev_cycle_count = 0;
210  uint8_t retries = 0;
211 
212  //If wheel diameter is set to 0 (or no wheels connected), the input value for linearX is equal to motors rpm
213  if(param_wheel_diameter_ == 0)
214  {
215  board_val = val / param_add_ratio_vel_;
216  }
217  else
218  {
219  //Formula to convert linear value to rpm (unit that the board accepts)
220  board_val = val * (SECS_TO_MIN / (PI * param_wheel_diameter_)) * (1 / param_add_ratio_vel_);
221  }
222 
223  ROS_DEBUG_STREAM("[" << __func__ << "] Subscriber callback entered, received: " << val << " board value: "
224  << board_val);
226 
227  while(retries <= param_SDO_PDO_retries_)
228  {
230  {
231  if(p_tmc_coe_interpreter_->input_pdo_[slave_number_]->modes_of_operation_display != PROFILE_VELOCITY)
232  {
234  }
235  p_tmc_coe_interpreter_->output_pdo_[slave_number_]->target_velocity = board_val;
236 
237  while((p_tmc_coe_interpreter_->getCycleCounter() - prev_cycle_count) < 1)
238  {
239  // Wait until it reaches next cycle
240  }
241 
242  if(p_tmc_coe_interpreter_->output_pdo_[slave_number_]->target_velocity == board_val)
243  {
244  ROS_DEBUG_STREAM("["<< __func__ << "] Subscriber callback exited successfully");
245  break;
246  }
247  prev_cycle_count = p_tmc_coe_interpreter_->getCycleCounter();
248  retries++;
249  }
250  }
252 
253  if(p_tmc_coe_interpreter_->output_pdo_[slave_number_]->target_velocity != board_val)
254  {
255  ROS_ERROR_STREAM("["<< __func__ << "] Failed to set Velocity");
256  }
257 }
258 
259 void TmcCoeBLDCMotor::cmdAbsPosCallback(const std_msgs::Int32 msg)
260 {
261  float convert_const_deg = 0.00;
262  int32_t unit_val = 0;
263  int32_t val = msg.data;
264 
265  //convert input(degrees) to unit
266  if(position_scaler_ > 0)
267  {
268  convert_const_deg = ((float)position_scaler_ / ANGULAR_FULL_ROTATION) * (1 / param_add_ratio_pos_);
269  }
270  else if(encoder_steps_ > 0)
271  {
272  convert_const_deg = ((float)encoder_steps_ / ANGULAR_FULL_ROTATION) * (1 / param_add_ratio_pos_);
273  }
274  else
275  {
276  //inverting position additional ratio
277  convert_const_deg = 1 / param_add_ratio_pos_;
278  }
279 
280  unit_val = val * convert_const_deg;
281 
282  ROS_DEBUG_STREAM("[" << __func__ << "] Subscriber callback entered, received: " << msg.data << " board value: "
283  << unit_val);
285 
287  {
289  {
290  if(p_tmc_coe_interpreter_->input_pdo_[slave_number_]->modes_of_operation_display != PROFILE_POSITION)
291  {
293  }
294  p_tmc_coe_interpreter_->output_pdo_[slave_number_]->target_position = unit_val;
296  }
297 
299  {
300  break;
301  }
302  }
305 
307  {
309  {
311  }
313  {
314  break;
315  }
316  }
318 
319  if(p_tmc_coe_interpreter_->output_pdo_[slave_number_]->target_position == unit_val)
320  {
321  ROS_DEBUG_STREAM("["<< __func__ << "] Subscriber callback exited successfully");
322  }
323  else
324  {
325  ROS_ERROR_STREAM("["<< __func__ << "] Failed to set Absolute Position");
326  }
327 }
328 
329 void TmcCoeBLDCMotor::cmdRelPosCallback(const std_msgs::Int32 msg)
330 {
331  float convert_const_deg = 0.00;
332  int32_t unit_val = 0;
333  int32_t val = msg.data;
334 
335  //convert input(degrees) to unit
336  if(position_scaler_ > 0)
337  {
338  convert_const_deg = ((float)position_scaler_ / ANGULAR_FULL_ROTATION) * (1 / param_add_ratio_pos_);
339  }
340  else if(encoder_steps_ > 0)
341  {
342  convert_const_deg = ((float)encoder_steps_ / ANGULAR_FULL_ROTATION) * (1 / param_add_ratio_pos_);
343  }
344  else
345  {
346  //inverting position additional ratio
347  convert_const_deg = 1 / param_add_ratio_pos_;
348  }
349 
350  unit_val = val * convert_const_deg;
351 
352  ROS_DEBUG_STREAM("[" << __func__ << "] Subscriber callback entered, received: " << msg.data << " board value: "
353  << unit_val);
355 
357  {
359  {
360  if(p_tmc_coe_interpreter_->input_pdo_[slave_number_]->modes_of_operation_display != PROFILE_POSITION)
361  {
363  }
364  p_tmc_coe_interpreter_->output_pdo_[slave_number_]->target_position = unit_val;
366  }
367 
369  {
370  break;
371  }
372  }
375 
377  {
379  {
381  }
383  {
384  break;
385  }
386  }
388 
389  if(p_tmc_coe_interpreter_->output_pdo_[slave_number_]->target_position == unit_val)
390  {
391  ROS_DEBUG_STREAM("["<< __func__ << "] Subscriber callback exited successfully");
392  }
393  else
394  {
395  ROS_ERROR_STREAM("["<< __func__ << "] Failed to set Relative Position");
396  }
397 }
SET_POINT_ACK_IN_PROCESS
@ SET_POINT_ACK_IN_PROCESS
Definition: tmc_coe_interpreter.h:60
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
TmcCoeInterpreter::input_pdo_
std::vector< input_pdo_t * > input_pdo_
Definition: tmc_coe_interpreter.h:200
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
PROFILE_VELOCITY
@ PROFILE_VELOCITY
Definition: tmc_coe_motor.h:20
PROFILE_POSITION
@ PROFILE_POSITION
Definition: tmc_coe_motor.h:19
TmcCoeMotor::param_interface_name_
std::string param_interface_name_
Definition: tmc_coe_motor.h:89
TmcCoeBLDCMotor::cmdAbsPosCallback
void cmdAbsPosCallback(const std_msgs::Int32 msg) override
Definition: tmc_coe_bldc_motor.cpp:259
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
TmcCoeInterpreter::readSDO
std::string readSDO(uint8_t slave_number, uint16_t index_number, uint16_t subindex_number, T value)
Definition: tmc_coe_interpreter.cpp:860
SECS_TO_MIN
const uint8_t SECS_TO_MIN
Definition: tmc_coe_motor.h:42
TmcCoeMotor::param_add_ratio_pos_
float param_add_ratio_pos_
Definition: tmc_coe_motor.h:87
ENABLE_OPERATION
@ ENABLE_OPERATION
Definition: tmc_coe_interpreter.h:32
TmcCoeBLDCMotor::initSubscriber
void initSubscriber() override
Definition: tmc_coe_bldc_motor.cpp:182
TmcCoeMotor::param_SDO_PDO_retries_
int param_SDO_PDO_retries_
Definition: tmc_coe_motor.h:75
TmcCoeMotor::param_add_ratio_trq_
float param_add_ratio_trq_
Definition: tmc_coe_motor.h:88
TmcCoeBLDCMotor::TmcCoeBLDCMotor
TmcCoeBLDCMotor(ros::NodeHandle *p_nh, TmcCoeInterpreter *p_tmc_coe_interpreter, uint8_t slave_number, uint8_t motor_number)
Definition: tmc_coe_bldc_motor.cpp:11
HOMING_MODE
@ HOMING_MODE
Definition: tmc_coe_motor.h:21
TmcCoeInterpreter::statusWordState
bool statusWordState(uint8_t slave_number, fsa_state_t state)
Definition: tmc_coe_interpreter.cpp:355
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
TmcCoeMotor::param_pub_actual_trq_
bool param_pub_actual_trq_
Definition: tmc_coe_motor.h:79
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
BLDC_DISABLED_MOTOR
@ BLDC_DISABLED_MOTOR
Definition: tmc_coe_bldc_motor.h:14
CYCLIC_SYNC_VEL
@ CYCLIC_SYNC_VEL
Definition: tmc_coe_motor.h:23
TmcCoeBLDCMotor::cmdRelPosCallback
void cmdRelPosCallback(const std_msgs::Int32 msg) override
Definition: tmc_coe_bldc_motor.cpp:329
BLDC_OPENLOOP_MOTOR
@ BLDC_OPENLOOP_MOTOR
Definition: tmc_coe_bldc_motor.h:15
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
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
TmcCoeBLDCMotor::position_scaler_
int32_t position_scaler_
Definition: tmc_coe_bldc_motor.h:33
TmcCoeInterpreter::isCycleFinished
bool isCycleFinished()
Definition: tmc_coe_interpreter.cpp:679
TmcCoeBLDCMotor::~TmcCoeBLDCMotor
~TmcCoeBLDCMotor()
Definition: tmc_coe_bldc_motor.cpp:19
TmcCoeInterpreter::stopCycleCounter
void stopCycleCounter()
Definition: tmc_coe_interpreter.cpp:707
TmcCoeBLDCMotor::cmdVelCallback
void cmdVelCallback(const geometry_msgs::Twist &msg) override
Definition: tmc_coe_bldc_motor.cpp:205
ros::TimerEvent
TmcCoeMotor::frame_id_
std::string frame_id_
Definition: tmc_coe_motor.h:59
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
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
TmcCoeInterpreter::getCycleCounter
uint8_t getCycleCounter()
Definition: tmc_coe_interpreter.cpp:689
TmcCoeMotor::tmc_coe_info_pub_
ros::Publisher tmc_coe_info_pub_
Definition: tmc_coe_motor.h:57
int32_t
signed int int32_t
ABSOLUTE_POSITION
@ ABSOLUTE_POSITION
Definition: tmc_coe_motor.h:30
TmcCoeInterpreter
Definition: tmc_coe_interpreter.h:148
NONE
@ NONE
Definition: tmc_coe_motor.h:18
TmcCoeInterpreter::output_pdo_
std::vector< output_pdo_t * > output_pdo_
Definition: tmc_coe_interpreter.h:201
TmcCoeInterpreter::startCycleCounter
void startCycleCounter()
Definition: tmc_coe_interpreter.cpp:698
TmcCoeMotor::p_tmc_coe_interpreter_
TmcCoeInterpreter * p_tmc_coe_interpreter_
Definition: tmc_coe_motor.h:93
TmcCoeBLDCMotor::init
void init() override
Definition: tmc_coe_bldc_motor.cpp:26
TmcCoeMotor::param_add_ratio_vel_
float param_add_ratio_vel_
Definition: tmc_coe_motor.h:86
bldc_comm_mode_t
bldc_comm_mode_t
Definition: tmc_coe_bldc_motor.h:12
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
tmc_coe_bldc_motor.h
TmcCoeMotor::param_pub_actual_vel_
bool param_pub_actual_vel_
Definition: tmc_coe_motor.h:77
TmcCoeBLDCMotor::rosPublishTmcCoeInfo
void rosPublishTmcCoeInfo(const ros::TimerEvent &event) override
Definition: tmc_coe_bldc_motor.cpp:102
TmcCoeBLDCMotor::encoder_steps_
uint32_t encoder_steps_
Definition: tmc_coe_bldc_motor.h:32
ros::NodeHandle
ros::Time::now
static Time now()
TmcCoeBLDCMotor::commutation_mode_
bldc_comm_mode_t commutation_mode_
Definition: tmc_coe_bldc_motor.h:34


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