motor.cpp
Go to the documentation of this file.
1 
31 #include "roboteq/motor.h"
32 
35 
38 
39 namespace roboteq {
40 
41 Motor::Motor(const ros::NodeHandle& nh, serial_controller *serial, string name, unsigned int number)
42  : DiagnosticTask(name + "_status")
43  , joint_state_handle(name, &position, &velocity, &effort)
44  , joint_handle(joint_state_handle, &command)
45  , mNh(nh)
46  , mSerial(serial)
47 {
48  // Initialize all variables
49  mNumber = number;
50  mMotorName = name;
51  command = 0;
52  // Reset variables
53  position = 0;
54  velocity = 0;
55  effort = 0;
56  // Initialize control mode
57  _control_mode = -1;
58 
59  // Initialize Dynamic reconfigurator for generic parameters
60  parameter = new MotorParamConfigurator(nh, serial, mMotorName, number);
61  // Initialize Dynamic reconfigurator for generic parameters
62  pid_velocity = new MotorPIDConfigurator(nh, serial, mMotorName, "velocity", number);
63  pid_torque = new MotorPIDConfigurator(nh, serial, mMotorName, "torque", number);
64  pid_position = new MotorPIDConfigurator(nh, serial, mMotorName, "position", number);
65 
66  // Add a status motor publisher
67  pub_status = mNh.advertise<roboteq_control::MotorStatus>(mMotorName + "/status", 10);
68  pub_control = mNh.advertise<roboteq_control::ControlStatus>(mMotorName + "/control", 10);
69 
70  // Add callback
71  // mSerial->addCallback(&Motor::read, this, "F" + std::to_string(mNumber));
72 }
73 
75 {
76  ROS_DEBUG_STREAM("Update: " << pub.getSubscriberName() << " - " << pub.getTopic());
77 }
78 
79 void Motor::initializeMotor(bool load_from_board)
80 {
81  // Initialize parameters
82  parameter->initConfigurator(load_from_board);
83  // Load PID configuration from roboteq board
84  // Get operative mode
86  bool tmp_pos = load_from_board & ((_control_mode == 2) || (_control_mode == 3) || (_control_mode == 4));
87  bool tmp_vel = load_from_board & ((_control_mode == 1) || (_control_mode == 6));
88  bool tmp_tor = load_from_board & (_control_mode == 5);
89 
90  // ROS_INFO_STREAM("Type pos:" << tmp_pos << " vel:" << tmp_vel << " tor:" << tmp_tor);
91 
92  // Initialize pid loader
94  // Initialize pid loader
96  // Initialize pid loader
97  pid_torque->initConfigurator(tmp_tor);
98 
99  // stop the motor
100  stopMotor();
101 }
102 
109 double Motor::to_encoder_ticks(double x)
110 {
111  double reduction = 0;
112  // Get ratio
113  mNh.getParam(mMotorName + "/ratio", reduction);
114  //ROS_INFO_STREAM("to_encoder_ticks:" << reduction);
115  // apply the reduction convertion
116  if(_sensor != NULL)
117  reduction = _sensor->getConversion(reduction);
118  // Return the value converted
119  return x * (reduction) / (2 * M_PI);
120 }
121 
129 {
130  double reduction = 0;
131  // Get ratio
132  mNh.getParam(mMotorName + "/ratio", reduction);
133  // apply the reduction convertion
134  if(_sensor != NULL)
135  reduction = _sensor->getConversion(reduction);
136  // Return the value converted
137  return x * (2 * M_PI) / (reduction);
138 }
139 
141 {
145 
146  bool state = true;
147 
148  // Manual value setting
149  limits.has_velocity_limits = true;
150  limits.max_velocity = 5.0;
151  limits.has_effort_limits = true;
152  limits.max_effort = 2.0;
153 
154  // Populate (soft) joint limits from URDF
155  // Limits specified in URDF overwrite existing values in 'limits' and 'soft_limits'
156  // Limits not specified in URDF preserve their existing values
157 
158  boost::shared_ptr<const urdf::Joint> urdf_joint = model.getJoint(mMotorName);
159  const bool urdf_limits_ok = getJointLimits(urdf_joint, limits);
160  const bool urdf_soft_limits_ok = getSoftJointLimits(urdf_joint, soft_limits);
161 
162  if(urdf_limits_ok) {
163  //ROS_INFO_STREAM("LOAD [" << mMotorName << "] limits from URDF: |" << limits.max_velocity << "| rad/s & |" << limits.max_effort << "| Nm");
164  state = false;
165  }
166 
167  if(urdf_soft_limits_ok) {
168  //ROS_INFO_STREAM("LOAD [" << mMotorName << "] soft limits from URDF: |" << limits.max_velocity << "| rad/s & |" << limits.max_effort << "| Nm");
169  state = false;
170  }
171 
172  // Populate (soft) joint limits from the ros parameter server
173  // Limits specified in the parameter server overwrite existing values in 'limits' and 'soft_limits'
174  // Limits not specified in the parameter server preserve their existing values
175  const bool rosparam_limits_ok = getJointLimits(mMotorName, mNh, limits);
176  if(rosparam_limits_ok) {
177  //ROS_WARN_STREAM("OVERLOAD [" << mMotorName << "] limits from ROSPARAM: |" << limits.max_velocity << "| rad/s & |" << limits.max_effort << "| Nm");
178  state = false;
179  }
180  else
181  {
182  //ROS_DEBUG("Setup limits, PARAM NOT available");
183  }
184  // If does not read any parameter from URDF or rosparm load default parameter
185  if(state)
186  {
187  //ROS_WARN_STREAM("LOAD [" << mMotorName << "] with DEFAULT limit = |" << limits.max_velocity << "| rad/s & |" << limits.max_effort << "| Nm");
188  }
189 
190  // Set maximum limits if doesn't have limit
191  if(limits.has_position_limits == false)
192  {
193  limits.max_position = 6.28;
194  }
195  // <<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<
196  // TODO CHECK HOW TO INITIALIZE
197  // Update limits
198  // max_position = limits.max_position;
199  // max_velocity = limits.max_velocity * params.ratio;
200  // max_effort = limits.max_effort;
201  // updateLimits(limits.max_position, limits.max_velocity, limits.max_effort);
202  // >>>>>>>>>>>>>>>>>>>>>>>>>>>>>>
203 
204  joint_limits_interface::VelocityJointSoftLimitsHandle handle(joint_handle, // We read the state and read/write the command
205  limits, // Limits spec
206  soft_limits); // Soft limits spec
207 
208  vel_limits_interface.registerHandle(handle);
209 }
210 
212 {
213  string control;
214  switch(_control_mode)
215  {
216  case -1:
217  control = "unset";
218  break;
219  case 0:
220  control = "Open loop";
221  break;
222  case 1:
223  control = "Closed loop speed";
224  break;
225  case 2:
226  control = "Closed loop position relative";
227  break;
228  case 3:
229  control = "Closed loop count position";
230  break;
231  case 4:
232  control = "Closed loop position tracking";
233  break;
234  case 5:
235  control = "Closed loop torque";
236  break;
237  case 6:
238  control = "Closed loop speed position";
239  break;
240  default:
241  control = "Error";
242  break;
243  }
244  stat.add("Control", control);
245 
246  stat.add("Motor number", mNumber);
247  stat.add("PWM rate (%)", msg_control.pwm);
248  stat.add("Voltage (V)", msg_status.volts);
249  stat.add("Battery (A)", msg_status.amps_batt);
250  stat.add("Watt motor (W)", msg_status.volts * msg_status.amps_motor);
251  stat.add("Watt batt (W)", msg_status.volts * msg_status.amps_batt);
252  stat.add("Loop error", msg_control.loop_error);
253  stat.add("Track", msg_status.track);
254  stat.add("Position (deg)", position);
255  stat.add("Velociy (RPM)", to_rpm(velocity));
256  stat.add("Current (A)", msg_status.amps_motor);
257  stat.add("Torque (Nm)", effort);
258 
259 
260  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Motor Ready!");
261 
262  if(_status.amps_limit)
263  {
264  stat.mergeSummaryf(diagnostic_msgs::DiagnosticStatus::ERROR, "Amps limits motor=%.2f", msg_status.amps_motor);
265  }
266 
268  {
269  stat.mergeSummary(diagnostic_msgs::DiagnosticStatus::WARN, "Amps trigger active");
270  }
271 
273  {
274  stat.mergeSummary(diagnostic_msgs::DiagnosticStatus::WARN, "Forward limit triggered");
275  }
276 
278  {
279  stat.mergeSummary(diagnostic_msgs::DiagnosticStatus::WARN, "Reverse limit triggered");
280  }
281 
283  {
284  stat.mergeSummary(diagnostic_msgs::DiagnosticStatus::ERROR, "Loop error detection");
285  }
286 
288  {
289  stat.mergeSummary(diagnostic_msgs::DiagnosticStatus::ERROR, "Motor stalled");
290  }
291 
293  {
294  stat.mergeSummary(diagnostic_msgs::DiagnosticStatus::WARN, "Safety stop active");
295  }
296 }
297 
299 {
300  // set to zero the reference
301  mSerial->command("G ", std::to_string(mNumber) + " 0");
302  // Stop motor [pag 222]
303  mSerial->command("MS", std::to_string(mNumber));
304 }
305 
306 void Motor::switchController(string type)
307 {
308  if(type.compare("diff_drive_controller/DiffDriveController") == 0)
309  {
310  // Load type of PID velocity
311  int pid_vel;
312  mNh.getParam(mMotorName + "/pid/closed_loop_velocity", pid_vel);
313  // ROS_INFO_STREAM("VEL mode:" << pid_vel);
314  // Set in speed position mode
315  parameter->setOperativeMode(pid_vel);
316  _control_mode = pid_vel;
317  }
318  else
319  {
320  _control_mode = -1;
321  // stop motor
322  stopMotor();
323  }
324 }
325 
327 {
328  // Send reset position
329  double enc_conv = to_encoder_ticks(position);
330  mSerial->command("C ", std::to_string(mNumber) + " " + std::to_string(enc_conv));
331  //mSerial->command("!C ", "2 " + std::to_string(enc_conv));
332 }
333 
335 {
336  // Enforce joint limits for all registered handles
337  // Note: one can also enforce limits on a per-handle basis: handle.enforceLimits(period)
339  // Get encoder max speed parameter
340  double max_rpm;
341  mNh.getParam(mMotorName + "/max_speed", max_rpm);
342  // Build a command message
343  long long int roboteq_velocity = static_cast<long long int>(to_rpm(command) / max_rpm * 1000.0);
344 
345  //ROS_INFO_STREAM("Velocity" << mNumber << " rad/s=" << command << " roboteq=" << roboteq_velocity);
346 
347  mSerial->command("G ", std::to_string(mNumber) + " " + std::to_string(roboteq_velocity));
348 }
349 
350 void Motor::read(string data) {
351  std::vector<std::string> fields;
352  boost::split(fields, data, boost::algorithm::is_any_of(":"));
353  // Decode list
354  readVector(fields);
355 }
356 
357 void Motor::readVector(std::vector<std::string> fields) {
358  double ratio, max_rpm;
359  // ROS_INFO_STREAM("Motor" << mNumber << " " << data);
360 
361 
362  // Get ratio
363  mNh.getParam(mMotorName + "/ratio", ratio);
364  // Get encoder max speed parameter
365  mNh.getParam(mMotorName + "/max_speed", max_rpm);
366  // Build messages
367  msg_status.header.stamp = ros::Time::now();
368  msg_control.header.stamp = ros::Time::now();
369 
370  // Scale factors as outlined in the relevant portions of the user manual, please
371  // see mbs/script.mbs for URL and specific page references.
372  try
373  {
374  // reference command FM <-> _MOTFLAG [pag. 246]
375  unsigned char status = boost::lexical_cast<unsigned int>(fields[0]);
376  memcpy(&_status, &status, sizeof(status));
377 
378  // reference command M <-> _MOTCMD [pag. 250]
379  double cmd = boost::lexical_cast<double>(fields[1]) * max_rpm / 1000.0;
380  msg_control.reference = (cmd / ratio);
381 
382  // reference command F <-> _FEEDBK [pag. 244]
383  double vel = boost::lexical_cast<double>(fields[2]) * max_rpm / 1000.0;
384  msg_control.feedback = (vel / ratio);
385  // Update velocity motor
386  velocity = (vel / ratio);
387 
388  // reference command E <-> _LPERR [pag. 243]
389  double loop_error = boost::lexical_cast<double>(fields[3]) * max_rpm / 1000.0;
390  msg_control.loop_error = (loop_error / ratio);
391 
392  // reference command P <-> _MOTPWR [pag. 255]
393  msg_control.pwm = boost::lexical_cast<double>(fields[4]);
394 
395  // reference voltage V <-> _VOLTS [pag. ---]
396  msg_status.volts = boost::lexical_cast<double>(fields[5]) / 10;
397 
398  // reference command A <-> _MOTAMPS [pag. 230]
399  msg_status.amps_motor = boost::lexical_cast<double>(fields[6]) / 10;
400 
401  // Evaluate effort
402  if(velocity != 0) effort = ((msg_status.volts * msg_status.amps_motor) / velocity) * ratio;
403  else effort = 0;
404 
405  // reference command BA <-> _BATAMPS [pag. 233]
406  msg_status.amps_motor = boost::lexical_cast<double>(fields[7]) / 10;
407 
408  // Reference command CR <-> _RELCNTR [pag. 241]
409  // To check and substitute with C
410  // Reference command C <-> _ABCNTR [pag. ---]
411  position = from_encoder_ticks(boost::lexical_cast<double>(fields[8]));
412 
413  // reference command TR <-> _TR [pag. 260]
414  msg_status.track = boost::lexical_cast<long>(fields[9]);
415 
416  //ROS_INFO_STREAM("[" << mNumber << "] track:" << msg_status.track);
417  //ROS_INFO_STREAM("[" << mNumber << "] volts:" << msg_status.volts << " - amps:" << msg_status.amps_motor);
418  //ROS_INFO_STREAM("[" << mNumber << "] status:" << status << " - pos:"<< position << " - vel:" << velocity << " - torque:");
419  }
420  catch (std::bad_cast& e)
421  {
422  ROS_WARN("Failure parsing feedback data. Dropping message.");
423  return;
424  }
425  // Publish status motor
427  // Publish status control motor
429 }
430 
431 }
double effort
Definition: motor.h:192
uint8_t loop_error_detect
Definition: motor.h:57
double to_encoder_ticks(double x)
Definition: motor.cpp:109
ros::Publisher pub_status
Definition: motor.h:202
roboteq_control::ControlStatus msg_control
Definition: motor.h:205
double command
Definition: motor.h:193
void publish(const boost::shared_ptr< M > &message) const
void summary(unsigned char lvl, const std::string s)
virtual double getConversion(double reduction)=0
double from_encoder_ticks(double x)
Definition: motor.cpp:128
uint8_t reverse_limit_triggered
Definition: motor.h:60
void run(diagnostic_updater::DiagnosticStatusWrapper &stat)
run Run the diagnostic updater
Definition: motor.cpp:211
void setOperativeMode(int type)
setOperativeMode Reference in page 321 - MMOD
Definition: motor_param.cpp:82
hardware_interface::JointHandle joint_handle
Definition: motor.h:140
void read(string data)
Definition: motor.cpp:350
bool getSoftJointLimits(const std::string &joint_name, const ros::NodeHandle &nh, SoftJointLimits &soft_limits)
void connectionCallback(const ros::SingleSubscriberPublisher &pub)
Definition: motor.cpp:74
uint8_t amps_limit
Definition: motor.h:55
uint8_t safety_stop_active
Definition: motor.h:58
joint_limits_interface::VelocityJointSoftLimitsInterface vel_limits_interface
ROS joint limits interface.
Definition: motor.h:199
#define ROS_WARN(...)
void enforceLimits(const ros::Duration &period)
void initConfigurator(bool load_from_board)
initConfigurator Initialize all parameter and syncronize parameters between ros and roboteq board ...
Definition: motor_param.cpp:45
std::string getTopic() const
GPIOSensor * _sensor
Definition: motor.h:212
uint8_t motor_stalled
Definition: motor.h:56
unsigned int mNumber
Definition: motor.h:143
void writeCommandsToHardware(ros::Duration period)
writeCommandsToHardware Write a command to the hardware interface
Definition: motor.cpp:334
status
bool getJointLimits(const std::string &joint_name, const ros::NodeHandle &nh, JointLimits &limits)
ROSLIB_DECL std::string command(const std::string &cmd)
void stopMotor()
stopMotor Stop the motor
Definition: motor.cpp:298
uint8_t amps_triggered_active
Definition: motor.h:61
std::string getSubscriberName() const
motor_status_t _status
Definition: motor.h:196
Motor(const ros::NodeHandle &nh, serial_controller *serial, string name, unsigned int number)
Motor The motor definition and all ros controller initializations are collected in this place...
Definition: motor.cpp:41
MotorPIDConfigurator * pid_position
Definition: motor.h:210
void resetPosition(double position)
resetPosition Reset the motor in a new initial position
Definition: motor.cpp:326
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
static double to_rpm(double x)
Definition: motor.h:149
#define ROS_DEBUG_STREAM(args)
ros::Publisher pub_control
Definition: motor.h:202
MotorParamConfigurator * parameter
Definition: motor.h:207
void mergeSummary(unsigned char lvl, const std::string s)
void setupLimits(urdf::Model model)
setupLimits setup the maximum velocity, positio and effort
Definition: motor.cpp:140
MotorPIDConfigurator * pid_velocity
Definition: motor.h:208
MotorPIDConfigurator * pid_torque
Definition: motor.h:209
void readVector(std::vector< std::string > fields)
readVector Decode vector data list
Definition: motor.cpp:357
bool command(string msg, string params="", string type="!")
Definition: motor.h:51
bool getParam(const std::string &key, std::string &s) const
uint8_t forward_limit_triggered
Definition: motor.h:59
static Time now()
void mergeSummaryf(unsigned char lvl, const char *format,...)
ros::NodeHandle mNh
Definition: motor.h:184
string mMotorName
Definition: motor.h:186
int _control_mode
Definition: motor.h:195
void add(const std::string &key, const T &val)
void switchController(string type)
switchController Switch the controller from different type of ros controller
Definition: motor.cpp:306
double velocity
Definition: motor.h:191
void initializeMotor(bool load_from_board)
initializeMotor Initialization oh motor, this routine load parameter from ros server or load from rob...
Definition: motor.cpp:79
roboteq_control::MotorStatus msg_status
Definition: motor.h:204
double position
Definition: motor.h:179
void initConfigurator(bool load_from_board)
Definition: motor_pid.cpp:48
serial_controller * mSerial
Definition: motor.h:188


roboteq_control
Author(s): Raffaello Bonghi
autogenerated on Wed Jan 3 2018 03:48:23