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> 64 boost::crc_32_type crc32;
66 return (this->
crc32_ == crc32.checksum());
71 boost::crc_32_type crc32;
73 this->
crc32_ = crc32.checksum();
92 if (!nh.
getParam(
"load_save_files", load_save_files_))
94 load_save_files_ =
true;
96 if (!nh.
getParam(
"update_save_files", update_save_files_))
98 update_save_files_ =
true;
100 if (!nh.
getParam(
"do_not_halt", disable_halt_))
104 disable_halt_ =
true;
106 if (!nh.
getParam(
"save_directory", save_directory_))
108 save_directory_ =
"/var/lib/motor_heating_model";
110 if (!nh.
getParam(
"enable_model", enable_model_))
112 enable_model_ =
true;
114 if (!nh.
getParam(
"publish_temperature", publish_temperature_))
116 publish_temperature_ =
false;
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 )
136 boost::lock_guard<boost::mutex> lock(
mutex_);
169 boost::lock_guard<boost::mutex> lock(
mutex_);
172 model->saveTemperatureState();
178 boost::lock_guard<boost::mutex> lock(
mutex_);
195 catch (
const std::exception &e)
197 ROS_ERROR(
"Error creating save directory '%s' for motor model : %s",
217 const std::string &actuator_name,
218 const std::string &hwid,
219 const std::string &save_directory
222 heating_energy_sum_(0.0),
223 ambient_temperature_sum_(0.0),
224 duration_since_last_sample_(0.0),
226 motor_params_(motor_params),
227 actuator_name_(actuator_name),
228 save_filename_(save_directory +
"/" + actuator_name_ +
".save"),
241 static const double default_ambient_temperature = 60.0;
258 std::string topic(
"motor_temperature");
265 ROS_ERROR(
"Could not allocate realtime publisher");
275 const ethercat_hardware::ActuatorInfo &ai)
285 double output_voltage = s.programmed_pwm * s.supply_voltage;
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;
290 double resistance_voltage = output_voltage - backemf_voltage;
293 double heating_power = resistance_voltage * s.measured_current;
297 if ((heating_power < -0.5) || (heating_power > 15.0))
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);
305 heating_power = std::max(heating_power, 0.0);
307 return heating_power;
316 double heating_energy = heating_power * duration;
317 double winding_energy_loss =
319 double housing_energy_loss =
326 boost::lock_guard<boost::mutex> lock(
mutex_);
340 double saved_ambient_temperature,
344 static const double heating_power = 0.0;
345 for (
unsigned i=0; i<cycles; ++i)
347 if (downtime > interval)
349 update(heating_power, saved_ambient_temperature, interval);
350 downtime -= interval;
355 update(heating_power, saved_ambient_temperature, downtime);
366 double saved_downtime = downtime;
380 ROS_DEBUG(
"Downtime too long, using ambient temperature as final motor temperature");
385 ROS_DEBUG(
"Took %f milliseconds to sim %f seconds", timer.elapsed()*1000., saved_downtime);
393 boost::lock_guard<boost::mutex> lock(
mutex_);
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;
412 boost::lock_guard<boost::mutex> lock(
mutex_);
419 if (duration_since_last_sample > 0.0)
421 average_ambient_temperature = ambient_temperature_sum / duration_since_last_sample;
429 average_heating_power = 0.0;
455 d.
addf(
"Motor winding temp (C)",
"%f", winding_temperature);
456 d.
addf(
"Motor housing temp (C)",
"%f", housing_temperature);
459 d.
addf(
"Heating power (Watts)",
"%f", average_heating_power);
460 d.
addf(
"Ambient temp (C)",
"%f", average_ambient_temperature);
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;
480 static bool getStringAttribute(TiXmlElement *elt,
const std::string& filename,
const char* param_name, std::string &value)
482 const char *val_str = elt->Attribute(param_name);
485 ROS_ERROR(
"No '%s' attribute for actuator '%s'", param_name, filename.c_str());
493 static bool getDoubleAttribute(TiXmlElement *elt,
const std::string& filename,
const char* param_name,
double &value)
495 const char *val_str = elt->Attribute(param_name);
498 ROS_ERROR(
"No '%s' attribute in '%s'", param_name, filename.c_str());
503 value = strtod(val_str, &endptr);
504 if ((endptr == val_str) || (endptr < (val_str+strlen(val_str))))
506 ROS_ERROR(
"Couldn't convert '%s' to double for attribute '%s' in '%s'",
507 val_str, param_name, filename.c_str());
515 static bool getIntegerAttribute(TiXmlElement *elt,
const std::string& filename,
const char* param_name,
int &value)
517 const char *val_str = elt->Attribute(param_name);
520 ROS_ERROR(
"No '%s' attribute in '%s'", param_name, filename.c_str());
525 value = strtol(val_str, &endptr, 0);
526 if ((endptr == val_str) || (endptr < (val_str+strlen(val_str))))
528 ROS_ERROR(
"Couldn't convert '%s' to integer for attribute '%s' in '%s'",
529 val_str, param_name, filename.c_str());
539 static const double max_realistic_temperature = 200.0;
540 static const double min_realistic_temperature = -10.0;
542 if (temperature > max_realistic_temperature)
544 ROS_WARN(
"%s temperature of %f Celcius is unrealisic. Using %f instead",
545 name, temperature, max_realistic_temperature);
546 temperature = max_realistic_temperature;
548 if (temperature < min_realistic_temperature)
550 ROS_WARN(
"%s temperature of %f Celcius is unrealisic. Using %f instead",
551 name, temperature, min_realistic_temperature);
552 temperature = min_realistic_temperature;
589 TiXmlElement *motor_temp_elt = xml.RootElement();
590 if (motor_temp_elt == NULL)
597 std::string actuator_name;
599 double winding_temperature;
600 double housing_temperature;
601 double ambient_temperature;
602 int save_time_sec, save_time_nsec;
607 const char* expected_version =
"1";
608 if (version != expected_version)
610 ROS_ERROR(
"Unknown version '%s', expected '%s'", version.c_str(), expected_version);
629 ROS_ERROR(
"In save file '%s' : expected actuator name '%s', got '%s'",
636 ROS_WARN(
"In save file '%s' : expected HWID '%s', got '%s'",
679 double winding_temperature;
680 double housing_temperature;
681 double ambient_temperature;
683 boost::lock_guard<boost::mutex> lock(
mutex_);
690 TiXmlDeclaration *decl =
new TiXmlDeclaration(
"1.0",
"",
"" );
691 TiXmlElement *elmt =
new TiXmlElement(
"motor_heating_model");
692 elmt->SetAttribute(
"version",
"1");
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);
699 elmt->SetAttribute(
"save_time_sec", now.
sec);
700 elmt->SetAttribute(
"save_time_nsec", now.
nsec);
702 xml.LinkEndChild(decl);
703 xml.LinkEndChild( elmt );
706 if (!xml.SaveFile(tmp_filename))
708 ROS_WARN(
"Could not save motor heating model file '%s'", tmp_filename.c_str());
717 if (strerror_r(error, errbuf,
sizeof(errbuf)) != 0)
719 memcpy(errbuf,
"Unknown error\0", 14);
721 errbuf[
sizeof(errbuf)-1] =
'\0';
722 ROS_WARN(
"Problem renaming '%s' to '%s' : (%d) '%s'",
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
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.
bool verifyCRC(void) const
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.
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.
bool startTemperaturePublisher()
std::string save_directory_
Directory where temperature save files should be put.
void saveThreadFunc()
Continuously saves motor heating model state.
bool saveTemperatureState()
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
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.
uint32_t crc32_
CRC32 of first 256-4 bytes of structure.
bool update(double heating_power, double ambient_temperature, double duration)
Updates motor temperature estimate.
std::string hwid_
Hardware ID of device (ex. 680500501000)