motor_heating_model.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
36 
37 #include <boost/crc.hpp>
38 #include <boost/static_assert.hpp>
39 #include <boost/filesystem.hpp>
40 #include <boost/bind.hpp>
41 #include <boost/foreach.hpp>
42 #include <boost/timer.hpp>
43 #include <boost/thread/mutex.hpp>
44 #include <boost/thread/thread.hpp>
45 
46 // Use XML format when saving or loading XML file
47 #include <tinyxml.h>
48 
49 #include <stdio.h>
50 #include <errno.h>
51 #include <exception>
52 
53 namespace ethercat_hardware
54 {
55 
56 
57 static const int DEBUG_LEVEL = 0;
58 
59 
61 {
62  BOOST_STATIC_ASSERT(sizeof(ethercat_hardware::MotorHeatingModelParametersEepromConfig) == 256);
63  BOOST_STATIC_ASSERT( offsetof(ethercat_hardware::MotorHeatingModelParametersEepromConfig, crc32_) == (256-4));
64  boost::crc_32_type crc32;
65  crc32.process_bytes(this, offsetof(MotorHeatingModelParametersEepromConfig, crc32_));
66  return (this->crc32_ == crc32.checksum());
67 }
68 
70 {
71  boost::crc_32_type crc32;
72  crc32.process_bytes(this, offsetof(MotorHeatingModelParametersEepromConfig, crc32_));
73  this->crc32_ = crc32.checksum();
74 }
75 
76 
77 
79 {
80  // There are a couple of rosparams that can be used to control the motor heating motor
81  // * <namespace>/motor_heating_model/load_save_files :
82  // boolean : defaults to true
83  // Do not load saved motor temperature data at startup .
84  // This might be useful for things like the the burn-in test stands
85  // where different parts are constantly switched in-and-out.
86  // * <namespace>/motor_heating_model/save_directory :
87  // string, defaults to '/var/lib'
88  // Location where motor heating model save data is loaded from and saved to
89  // * <namespace>/motor_heating_model/do_not_halt :
90  // boolean, defaults to false
91  //
92  if (!nh.getParam("load_save_files", load_save_files_))
93  {
94  load_save_files_ = true;
95  }
96  if (!nh.getParam("update_save_files", update_save_files_))
97  {
98  update_save_files_ = true;
99  }
100  if (!nh.getParam("do_not_halt", disable_halt_))
101  {
102  // TODO : once there has been enough testing of motor heating model on robot in real-world conditions,
103  // enable halting by default
104  disable_halt_ = true;
105  }
106  if (!nh.getParam("save_directory", save_directory_))
107  {
108  save_directory_ = "/var/lib/motor_heating_model";
109  }
110  if (!nh.getParam("enable_model", enable_model_))
111  {
112  enable_model_ = true;
113  }
114  if (!nh.getParam("publish_temperature", publish_temperature_))
115  {
116  publish_temperature_ = false;
117  }
118 }
119 
120 
122  update_save_files_ ( true ),
123  save_directory_ ("/var/lib/motor_heating_model" ),
124  load_save_files_ ( true ),
125  disable_halt_ ( false ),
126  enable_model_( true ),
127  publish_temperature_( false )
128 {
129 
130 }
131 
132 
134 {
135  { // LOCK
136  boost::lock_guard<boost::mutex> lock(mutex_);
137  models_.push_back(model);
138  } // UNLOCK
139 }
140 
141 
143 {
144  if (update_save_files_)
145  {
146  // Save thread should not be started until all MotorHeatingModels have been attached()
147  save_thread_ = boost::thread(boost::bind(&MotorHeatingModelCommon::saveThreadFunc, this));
148  }
149  return true;
150 }
151 
152 
161 {
162  // DEB install should create directory with proper permissions.
163  //createSaveDirectory();
164 
165  while (true)
166  {
167  sleep(10);
168  { //LOCK
169  boost::lock_guard<boost::mutex> lock(mutex_);
170  BOOST_FOREACH( boost::shared_ptr<MotorHeatingModel> model, models_ )
171  {
172  model->saveTemperatureState();
173  }
174  } //UNLOCK
175  }
176 
177  { // Throw away ptrs to all motor models
178  boost::lock_guard<boost::mutex> lock(mutex_);
179  models_.clear();
180  }
181 }
182 
183 
187 {
188  // create save directory if it does not already exist
189  if (!boost::filesystem::exists(save_directory_))
190  {
191  ROS_WARN("Motor heating motor save directory '%s' does not exist, creating it", save_directory_.c_str());
192  try {
193  boost::filesystem::create_directory(save_directory_);
194  }
195  catch (const std::exception &e)
196  {
197  ROS_ERROR("Error creating save directory '%s' for motor model : %s",
198  save_directory_.c_str(), e.what());
199  return false;
200  }
201  }
202 
203  return true;
204 }
205 
206 
207 
217  const std::string &actuator_name,
218  const std::string &hwid,
219  const std::string &save_directory
220  ) :
221  overheat_(false),
222  heating_energy_sum_(0.0),
223  ambient_temperature_sum_(0.0),
224  duration_since_last_sample_(0.0),
225  publisher_(NULL),
226  motor_params_(motor_params),
227  actuator_name_(actuator_name),
228  save_filename_(save_directory + "/" + actuator_name_ + ".save"),
229  hwid_(hwid)
230 {
231 
232 
233 
234  // If the guess is too low, the motors may not halt when they get too hot.
235  // If the guess is too high the motor may halt when they should not.
236 
237  // The first time the motor heating model is run on new machine, there will be no saved motor temperature data.
238  // With the saved temperatures, we have to 'guess' an initial motor temperature.
239  // Because the motor have been used for multiple years with only a couple incidents,
240  // its probably better to error on the side of false negitives.
241  static const double default_ambient_temperature = 60.0;
242  winding_temperature_ = default_ambient_temperature;
243  housing_temperature_ = default_ambient_temperature;
244  ambient_temperature_ = default_ambient_temperature;
245 
246  // Calculate internal parameters from motor parameters
253 }
254 
255 
257 {
258  std::string topic("motor_temperature");
259  if (!actuator_name_.empty())
260  {
261  topic = topic + "/" + actuator_name_;
263  if (publisher_ == NULL)
264  {
265  ROS_ERROR("Could not allocate realtime publisher");
266  return false;
267  }
268  }
269  return true;
270 }
271 
272 
273 
274 double MotorHeatingModel::calculateMotorHeatPower(const ethercat_hardware::MotorTraceSample &s,
275  const ethercat_hardware::ActuatorInfo &ai)
276 {
277  // Normally the power being put into motor is I^2*R.
278  // However, the motor resistance changes with temperature
279  // Instead this fuction breaks motor voltage into two parts
280  // 1. back-EMF voltage
281  // 2. resistance voltage
282  // Then the power being put into motor is (resistance voltage * I)
283 
284  // Output voltage of MCB. Guesstimate by multipling pwm ratio with supply voltage
285  double output_voltage = s.programmed_pwm * s.supply_voltage;
286  // Back emf voltage of motor
287  double backemf_constant = 1.0 / (ai.speed_constant * 2.0 * M_PI * 1.0/60.0);
288  double backemf_voltage = s.velocity * ai.encoder_reduction * backemf_constant;
289  // What ever voltage is left over must be the voltage used to drive current through the motor
290  double resistance_voltage = output_voltage - backemf_voltage;
291 
292  // Power going into motor as heat (Watts)
293  double heating_power = resistance_voltage * s.measured_current;
294 
295  if (DEBUG_LEVEL) // Only use for debugging, (prints out debug info for unreasonable heating values)
296  {
297  if ((heating_power < -0.5) || (heating_power > 15.0))
298  {
299  ROS_DEBUG("heating power = %f, output_voltage=%f, backemf_voltage=%f, resistance_voltage=%f, current=%f",
300  heating_power, output_voltage, backemf_voltage, resistance_voltage, s.measured_current);
301  }
302  }
303 
304  // Heating power can never be less than 0.0
305  heating_power = std::max(heating_power, 0.0);
306 
307  return heating_power;
308 }
309 
310 
311 bool MotorHeatingModel::update(double heating_power, double ambient_temperature, double duration)
312 {
313  // motor winding gains heat power (from motor current)
314  // motor winding losses heat to motor housing
315  // motor housing gets heat from winding and looses heat to ambient
316  double heating_energy = heating_power * duration;
317  double winding_energy_loss =
319  double housing_energy_loss =
320  (housing_temperature_ - ambient_temperature) * housing_to_ambient_thermal_conductance_ * duration;
321 
322  winding_temperature_ += (heating_energy - winding_energy_loss) * winding_thermal_mass_inverse_;
323  housing_temperature_ += (winding_energy_loss - housing_energy_loss) * housing_thermal_mass_inverse_;
324 
325  { // LOCKED
326  boost::lock_guard<boost::mutex> lock(mutex_);
327  heating_energy_sum_ += heating_energy;
328  ambient_temperature_sum_ += (ambient_temperature * duration);
329  duration_since_last_sample_ += duration;
331  overheat_ = true;
332  } // LOCKED
333 
334  return !overheat_;
335 }
336 
337 
338 
340  double saved_ambient_temperature,
341  double interval,
342  unsigned cycles)
343 {
344  static const double heating_power = 0.0; // While motor was off heating power should be zero
345  for (unsigned i=0; i<cycles; ++i)
346  {
347  if (downtime > interval)
348  {
349  update(heating_power, saved_ambient_temperature, interval);
350  downtime -= interval;
351  }
352  else
353  {
354  // Done
355  update(heating_power, saved_ambient_temperature, downtime);
356  return 0.0;
357  }
358  }
359  return downtime;
360 }
361 
362 
363 void MotorHeatingModel::updateFromDowntime(double downtime, double saved_ambient_temperature)
364 {
365  ROS_DEBUG("Initial temperatures : winding = %f, housing = %f", winding_temperature_, housing_temperature_);
366  double saved_downtime = downtime;
367 
368  boost::timer timer;
369 
370  // Simulate motor heating model first with increasing step sizes :
371  // first 10 ms, then 100ms, and finally 1 seconds steps
372  downtime = updateFromDowntimeWithInterval(downtime, saved_ambient_temperature, 0.01, 200);
373  downtime = updateFromDowntimeWithInterval(downtime, saved_ambient_temperature, 0.10, 200);
374  downtime = updateFromDowntimeWithInterval(downtime, saved_ambient_temperature, 1.00, 200);
375  downtime = updateFromDowntimeWithInterval(downtime, saved_ambient_temperature, 10.0, 2000);
376 
377  // If there is any time left over, assume motor has cooled to ambient
378  if (downtime > 0.0)
379  {
380  ROS_DEBUG("Downtime too long, using ambient temperature as final motor temperature");
381  winding_temperature_ = saved_ambient_temperature;
382  housing_temperature_ = saved_ambient_temperature;
383  }
384 
385  ROS_DEBUG("Took %f milliseconds to sim %f seconds", timer.elapsed()*1000., saved_downtime);
386  ROS_DEBUG("Final temperatures : winding = %f, housing = %f", winding_temperature_, housing_temperature_);
387 }
388 
389 
391 {
392  { // LOCKED
393  boost::lock_guard<boost::mutex> lock(mutex_);
394  overheat_ = false;
395  } // LOCKED
396 }
397 
398 
400 {
401  // Sample motor temperature and heating energy every so often, this way the
402  // heating of the motor can be published when there is a problem
403  bool overheat;
404  double winding_temperature;
405  double housing_temperature;
406  double ambient_temperature_sum;
407  double duration_since_last_sample;
408  double average_ambient_temperature;
409  double average_heating_power;
410 
411  { // LOCKED
412  boost::lock_guard<boost::mutex> lock(mutex_);
413  overheat = overheat_;
414  winding_temperature = winding_temperature_;
415  housing_temperature = housing_temperature_;
416  ambient_temperature_sum = ambient_temperature_sum_;
417  duration_since_last_sample = duration_since_last_sample_;
418 
419  if (duration_since_last_sample > 0.0)
420  {
421  average_ambient_temperature = ambient_temperature_sum / duration_since_last_sample;
422  ambient_temperature_ = average_ambient_temperature;
423  average_heating_power = heating_energy_sum_ / duration_since_last_sample;
424  }
425  else
426  {
427  //ROS_WARN("Duration == 0");
428  average_ambient_temperature = ambient_temperature_;
429  average_heating_power = 0.0;
430  }
431 
433  heating_energy_sum_ = 0.0;
435  } // LOCKED
436 
437 
438 
439  const int ERROR = 2;
440  const int WARN = 1;
441  //const int GOOD = 0;
442 
443  if (overheat)
444  {
445  // Once motor overheating flag is set, keep reporting motor has overheated, until the flag is reset.
446  d.mergeSummary(ERROR, "Motor overheated");
447  }
448  else if (winding_temperature > (motor_params_.max_winding_temperature_ * 0.90))
449  {
450  // If motor winding temperature reaches 90% of limit, then make a warning
451  d.mergeSummary(WARN, "Motor hot");
452  }
453 
454  d.addf("Motor winding temp limit (C)", "%f", motor_params_.max_winding_temperature_);
455  d.addf("Motor winding temp (C)", "%f", winding_temperature);
456  d.addf("Motor housing temp (C)", "%f", housing_temperature);
457 
458  // TODO: removing this, probably not need for purposes other than debugging
459  d.addf("Heating power (Watts)", "%f", average_heating_power);
460  d.addf("Ambient temp (C)", "%f", average_ambient_temperature);
461 
462 
463  if ((publisher_ != NULL) && (publisher_->trylock()))
464  {
465  // Fill in sample values
466  ethercat_hardware::MotorTemperature &msg(publisher_->msg_);
467  msg.stamp = ros::Time::now();
468  msg.winding_temperature = winding_temperature;
469  msg.housing_temperature = housing_temperature;
470  msg.ambient_temperature = average_ambient_temperature;
471  msg.heating_power = average_heating_power;
472 
473  // publish sample
475  }
476 }
477 
478 
479 
480 static bool getStringAttribute(TiXmlElement *elt, const std::string& filename, const char* param_name, std::string &value)
481 {
482  const char *val_str = elt->Attribute(param_name);
483  if (val_str == NULL)
484  {
485  ROS_ERROR("No '%s' attribute for actuator '%s'", param_name, filename.c_str());
486  return false;
487  }
488  value = val_str;
489  return true;
490 }
491 
492 
493 static bool getDoubleAttribute(TiXmlElement *elt, const std::string& filename, const char* param_name, double &value)
494 {
495  const char *val_str = elt->Attribute(param_name);
496  if (val_str == NULL)
497  {
498  ROS_ERROR("No '%s' attribute in '%s'", param_name, filename.c_str());
499  return false;
500  }
501 
502  char *endptr=NULL;
503  value = strtod(val_str, &endptr);
504  if ((endptr == val_str) || (endptr < (val_str+strlen(val_str))))
505  {
506  ROS_ERROR("Couldn't convert '%s' to double for attribute '%s' in '%s'",
507  val_str, param_name, filename.c_str());
508  return false;
509  }
510 
511  return true;
512 }
513 
514 
515 static bool getIntegerAttribute(TiXmlElement *elt, const std::string& filename, const char* param_name, int &value)
516 {
517  const char *val_str = elt->Attribute(param_name);
518  if (val_str == NULL)
519  {
520  ROS_ERROR("No '%s' attribute in '%s'", param_name, filename.c_str());
521  return false;
522  }
523 
524  char *endptr=NULL;
525  value = strtol(val_str, &endptr, 0);
526  if ((endptr == val_str) || (endptr < (val_str+strlen(val_str))))
527  {
528  ROS_ERROR("Couldn't convert '%s' to integer for attribute '%s' in '%s'",
529  val_str, param_name, filename.c_str());
530  return false;
531  }
532 
533  return true;
534 }
535 
536 
537 static void saturateTemperature(double &temperature, const char *name)
538 {
539  static const double max_realistic_temperature = 200.0;
540  static const double min_realistic_temperature = -10.0;
541 
542  if (temperature > max_realistic_temperature)
543  {
544  ROS_WARN("%s temperature of %f Celcius is unrealisic. Using %f instead",
545  name, temperature, max_realistic_temperature);
546  temperature = max_realistic_temperature;
547  }
548  if (temperature < min_realistic_temperature)
549  {
550  ROS_WARN("%s temperature of %f Celcius is unrealisic. Using %f instead",
551  name, temperature, min_realistic_temperature);
552  temperature = min_realistic_temperature;
553  }
554 }
555 
556 
558 {
559  /*
560  * The tempature save file will be named after the actuator it was created for
561  * <actuactor_name>_motor_heating_model.save
562  *
563  * The temperatureState file will have a XML format:
564  * <motor_heating_model
565  * version = "1"
566  * actuator_name = "fl_caster_r_wheel_motor"
567  * winding_temperature = "100.0"
568  * housing_temperature = "100.0"
569  * save_time = "<wall_time when file was lasted saved>"
570  * checksum = "<CRC32 of all previous lines in file>, to allow user editing of files checksum can be "IGNORE-CRC"
571  * />
572  *
573  */
574 
575  if (!boost::filesystem::exists(save_filename_))
576  {
577  ROS_WARN("Motor heating model saved file '%s' does not exist. Using defaults", save_filename_.c_str());
578  return false;
579  }
580 
581  TiXmlDocument xml;
582  if (!xml.LoadFile(save_filename_))
583  {
584  ROS_ERROR("Unable to parse XML in save file '%s'", save_filename_.c_str());
585  return false;
586  }
587 
588 
589  TiXmlElement *motor_temp_elt = xml.RootElement();
590  if (motor_temp_elt == NULL)
591  {
592  ROS_ERROR("Unable to parse XML in save file '%s'", save_filename_.c_str());
593  return false;
594  }
595 
596  std::string version;
597  std::string actuator_name;
598  std::string hwid;
599  double winding_temperature;
600  double housing_temperature;
601  double ambient_temperature;
602  int save_time_sec, save_time_nsec;
603  if (!getStringAttribute(motor_temp_elt, save_filename_, "version", version))
604  {
605  return false;
606  }
607  const char* expected_version = "1";
608  if (version != expected_version)
609  {
610  ROS_ERROR("Unknown version '%s', expected '%s'", version.c_str(), expected_version);
611  return false;
612  }
613 
614  bool success = true;
615  success &= getStringAttribute(motor_temp_elt, save_filename_, "actuator_name", actuator_name);
616  success &= getStringAttribute(motor_temp_elt, save_filename_, "hwid", hwid);
617  success &= getDoubleAttribute(motor_temp_elt, save_filename_, "housing_temperature", housing_temperature);
618  success &= getDoubleAttribute(motor_temp_elt, save_filename_, "winding_temperature", winding_temperature);
619  success &= getDoubleAttribute(motor_temp_elt, save_filename_, "ambient_temperature", ambient_temperature);
620  success &= getIntegerAttribute(motor_temp_elt, save_filename_, "save_time_sec", save_time_sec);
621  success &= getIntegerAttribute(motor_temp_elt, save_filename_, "save_time_nsec", save_time_nsec);
622  if (!success)
623  {
624  return false;
625  }
626 
627  if (actuator_name != actuator_name_)
628  {
629  ROS_ERROR("In save file '%s' : expected actuator name '%s', got '%s'",
630  save_filename_.c_str(), actuator_name_.c_str(), actuator_name.c_str());
631  return false;
632  }
633 
634  if (hwid != hwid_)
635  {
636  ROS_WARN("In save file '%s' : expected HWID '%s', got '%s'",
637  save_filename_.c_str(), hwid_.c_str(), hwid.c_str());
638  }
639 
640  saturateTemperature(housing_temperature, "Housing");
641  saturateTemperature(winding_temperature, "Winding");
642  saturateTemperature(ambient_temperature, "Ambient");
643 
644  // Update stored temperatures
645  winding_temperature_ = winding_temperature;
646  housing_temperature_ = housing_temperature;
647  ambient_temperature_ = ambient_temperature;
648 
649  // Update motor temperature model based on saved time, update time, and saved ambient temperature
650  double downtime = (ros::Time::now() - ros::Time(save_time_sec, save_time_nsec)).toSec();
651  if (downtime < 0.0)
652  {
653  ROS_WARN("In save file '%s' : save time is %f seconds in future", save_filename_.c_str(), -downtime);
654  }
655  else
656  {
657  updateFromDowntime(downtime, ambient_temperature);
658  }
659 
660  // Make sure simulation didn't go horribly wrong
663 
664  return true;
665 }
666 
667 
668 
669 
670 
672 {
673  /*
674  * This will first generate new XML data into temp file, then rename temp file to final filename
675  *
676  */
677  std::string tmp_filename = save_filename_ + ".tmp";
678 
679  double winding_temperature;
680  double housing_temperature;
681  double ambient_temperature;
682  { // LOCKED
683  boost::lock_guard<boost::mutex> lock(mutex_);
684  winding_temperature = winding_temperature_;
685  housing_temperature = housing_temperature_;
686  ambient_temperature = ambient_temperature_;
687  } // LOCKED
688 
689  TiXmlDocument xml;
690  TiXmlDeclaration *decl = new TiXmlDeclaration( "1.0", "", "" );
691  TiXmlElement *elmt = new TiXmlElement("motor_heating_model");
692  elmt->SetAttribute("version", "1");
693  elmt->SetAttribute("actuator_name", actuator_name_);
694  elmt->SetAttribute("hwid", hwid_);
695  elmt->SetDoubleAttribute("winding_temperature", winding_temperature);
696  elmt->SetDoubleAttribute("housing_temperature", housing_temperature);
697  elmt->SetDoubleAttribute("ambient_temperature", ambient_temperature);
698  ros::Time now = ros::Time::now();
699  elmt->SetAttribute("save_time_sec", now.sec);
700  elmt->SetAttribute("save_time_nsec", now.nsec);
701 
702  xml.LinkEndChild(decl);
703  xml.LinkEndChild( elmt );
704 
705  // save xml with temporary filename
706  if (!xml.SaveFile(tmp_filename))
707  {
708  ROS_WARN("Could not save motor heating model file '%s'", tmp_filename.c_str());
709  return false;
710  }
711 
712  // now rename file
713  if (rename(tmp_filename.c_str(), save_filename_.c_str()) != 0)
714  {
715  int error = errno;
716  char errbuf[100];
717  if (strerror_r(error, errbuf, sizeof(errbuf)) != 0)
718  {
719  memcpy(errbuf, "Unknown error\0", 14);
720  }
721  errbuf[sizeof(errbuf)-1] = '\0';
722  ROS_WARN("Problem renaming '%s' to '%s' : (%d) '%s'",
723  tmp_filename.c_str(), save_filename_.c_str(), error, errbuf);
724  return false;
725  }
726 
727  return true;
728 }
729 
730 
731 
732 }; // end namespace ethercat_hardware
msg
double winding_thermal_time_constant_
Thermal time constant of motor winding : in seconds.
static bool getDoubleAttribute(TiXmlElement *elt, const std::string &filename, const char *param_name, double &value)
static const int DEBUG_LEVEL
static void saturateTemperature(double &temperature, const char *name)
std::string save_filename_
path to file where temperature data will be saved
WARN
double updateFromDowntimeWithInterval(double downtime, double saved_ambient_temperature, double interval, unsigned cycles)
Updates estimated motor temperature for certain amount of downtime.
bool overheat_
True if most has overheat, once set, will only clear when reset() is called.
MotorHeatingModelCommon()
Constructor will use default settings for all parameters.
double calculateMotorHeatPower(const ethercat_hardware::MotorTraceSample &sample, const ethercat_hardware::ActuatorInfo &actuator_info)
static bool getStringAttribute(TiXmlElement *elt, const std::string &filename, const char *param_name, std::string &value)
double heating_energy_sum_
Sum of heat energy for last sample interval.
#define ROS_WARN(...)
void addf(const std::string &key, const char *format,...)
MotorHeatingModel(const MotorHeatingModelParameters &motor_params, const std::string &actuator_name, const std::string &hwid, const std::string &save_directory)
Constructor.
std::string save_directory_
Directory where temperature save files should be put.
void saveThreadFunc()
Continuously saves motor heating model state.
void diagnostics(diagnostic_updater::DiagnosticStatusWrapper &d)
Appends heating diagnostic data to status wrapper.
boost::mutex mutex_
Lock around models list.
double winding_to_housing_thermal_resistance_
Thermal resistance between motor winding and motor housing : in C/Watt.
void updateFromDowntime(double downtime, double saved_ambient_temperature)
Updates estimated motor temperature for long period of off-time.
realtime_tools::RealtimePublisher< ethercat_hardware::MotorTemperature > * publisher_
Sample interval for trace (in seconds)
std::vector< boost::shared_ptr< MotorHeatingModel > > models_
List of MotorHeatingModels that need to have file data saved.
double winding_thermal_mass_inverse_
Inverse of thermal mass for motor winding : in Joules/C.
double duration_since_last_sample_
Time (in seconds) since late sample interval occurred.
MotorHeatingModelParameters motor_params_
std::string actuator_name_
name of actuator (ex. fl_caster_rotation_motor)
bool createSaveDirectory()
Creates directory for saved motor heating information.
double housing_thermal_time_constant_
Thermal time constant of motor housing : in seconds.
double winding_temperature_
Temperature estimate of motor winding : in Celcius.
static bool getIntegerAttribute(TiXmlElement *elt, const std::string &filename, const char *param_name, int &value)
void attach(boost::shared_ptr< MotorHeatingModel > model)
Append model to list of models that need to have temperature data saved.
double max_winding_temperature_
temperature limit of motor windings : in Celcius
bool loadTemperatureState()
Load saved temperature estimate from directory.
void mergeSummary(unsigned char lvl, const std::string s)
double housing_to_ambient_thermal_conductance_
Thermal conductance between motor housing and ambient : in Watt/C.
double housing_thermal_mass_inverse_
Inverse of thermal mass for motor housing : in Joules/C.
double ambient_temperature_
Last recorded ambient temperature : in Celcius.
void reset()
Resets motor overheat flag.
double winding_to_housing_thermal_conductance_
Thermal conductance between motor winding and housing : in Watt/C.
bool getParam(const std::string &key, std::string &s) const
static Time now()
double housing_to_ambient_thermal_resistance_
Thermal resistance between motor housing and ambient : in C/Watt.
boost::thread save_thread_
thread that will periodically save temperature data
double ambient_temperature_sum_
Sum of (abient heat * time) over last sample interval.
boost::mutex mutex_
mutex protects values updates by realtime thread and used by diagnostics thread
double housing_temperature_
Temperature estimate of motor housing : in Celcius.
#define ROS_ERROR(...)
uint32_t crc32_
CRC32 of first 256-4 bytes of structure.
ERROR
bool update(double heating_power, double ambient_temperature, double duration)
Updates motor temperature estimate.
std::string hwid_
Hardware ID of device (ex. 680500501000)
#define ROS_DEBUG(...)


ethercat_hardware
Author(s): Rob Wheeler , Derek King
autogenerated on Thu Mar 4 2021 03:10:21