13 TmcCoeMotor(p_nh, p_tmc_coe_interpreter, slave_number, motor_number)
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";
45 ROS_ERROR_STREAM(
"[" << __func__ <<
"] Object Name for Commutation Mode is not Available");
57 ROS_ERROR_STREAM(
"[" << __func__ <<
"] Object Name for Position Scaler not Available");
71 ROS_ERROR_STREAM(
"[" << __func__ <<
"] Object Name for Encoder Steps not Available");
104 std::string mode_of_operation =
"";
120 case NONE: mode_of_operation =
"None";
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;
198 ROS_INFO_STREAM(
"[" << __func__ <<
"] Commutation Mode : CLOSED LOOP");
207 float val = msg.linear.x;
223 ROS_DEBUG_STREAM(
"[" << __func__ <<
"] Subscriber callback entered, received: " << val <<
" board value: "
244 ROS_DEBUG_STREAM(
"["<< __func__ <<
"] Subscriber callback exited successfully");
261 float convert_const_deg = 0.00;
280 unit_val = val * convert_const_deg;
282 ROS_DEBUG_STREAM(
"[" << __func__ <<
"] Subscriber callback entered, received: " << msg.data <<
" board value: "
321 ROS_DEBUG_STREAM(
"["<< __func__ <<
"] Subscriber callback exited successfully");
331 float convert_const_deg = 0.00;
350 unit_val = val * convert_const_deg;
352 ROS_DEBUG_STREAM(
"[" << __func__ <<
"] Subscriber callback entered, received: " << msg.data <<
" board value: "
391 ROS_DEBUG_STREAM(
"["<< __func__ <<
"] Subscriber callback exited successfully");