motor_heating_model.h
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 
35 #ifndef ETHERCAT_HARDWARE__MOTOR_HEATING_MODEL_H
36 #define ETHERCAT_HARDWARE__MOTOR_HEATING_MODEL_H
37 
38 #include "ethercat_hardware/MotorTemperature.h"
39 #include "ethercat_hardware/MotorTraceSample.h"
40 #include "ethercat_hardware/ActuatorInfo.h"
41 
44 
45 #include <boost/utility.hpp>
46 #include <boost/thread/mutex.hpp>
47 #include <boost/thread/thread.hpp>
48 #include <boost/shared_ptr.hpp>
49 
50 #include <vector>
51 #include <string>
52 
54 {
55 
56 
63 {
74 } __attribute__ ((__packed__));
75 
76 
88 {
89  uint16_t major_;
90  uint16_t minor_;
91  bool enforce_;
92  uint8_t pad1[3];
94  uint8_t pad2[204];
95  uint32_t crc32_;
96 
97  static const unsigned EEPROM_PAGE = 4093; // Acutator info on page 4095, MCB config on 4094
98 
99  bool verifyCRC(void) const;
100  void generateCRC(void);
101 } __attribute__ ((__packed__));
102 
103 
104 class MotorHeatingModel;
105 
106 class MotorHeatingModelCommon : private boost::noncopyable
107 {
108 public:
112 
116 
117 
118  bool initialize();
119 
123 
128  std::string save_directory_;
130  bool load_save_files_;
132  bool disable_halt_;
134  bool enable_model_;
137 
138 protected:
139  bool createSaveDirectory();
140 
142  boost::thread save_thread_;
143  void saveThreadFunc();
144 
146  std::vector< boost::shared_ptr<MotorHeatingModel> > models_;
147 
149  boost::mutex mutex_;
150 };
151 
152 
153 
154 class MotorHeatingModel : private boost::noncopyable
155 {
156 public:
157 
159  const std::string &actuator_name,
160  const std::string &hwid,
161  const std::string &save_directory
162  );
163 
165 
176  bool update(double heating_power, double ambient_temperature, double duration);
177  bool update(const ethercat_hardware::MotorTraceSample &sample,
178  const ethercat_hardware::ActuatorInfo &actuator_info,
179  double ambient_temperature, double duration)
180  {
181  double heating_power = calculateMotorHeatPower(sample, actuator_info);
182  return update(heating_power, ambient_temperature, duration);
183  }
184 
186  bool hasOverheated() const {return overheat_;}
191 
192 
194  void reset();
195 
196 
208  void updateFromDowntime(double downtime, double saved_ambient_temperature);
209 
210 
218  double updateFromDowntimeWithInterval(double downtime,
219  double saved_ambient_temperature,
220  double interval,
221  unsigned cycles);
222 
223 
226  double calculateMotorHeatPower(const ethercat_hardware::MotorTraceSample &sample,
227  const ethercat_hardware::ActuatorInfo &actuator_info);
228 
229 
231  bool loadTemperatureState();
232 
233 
239  bool saveTemperatureState();
240 
241 
244 
245 
246 
247 
248 protected:
249  // Following values are calculated from motor parameters.
250  // They are more useful when peforming motor model calculations
251  //
252  // Thermal is conducance amount of heat power tranfered for a
253  // given temperature differential
254  // Thermal conductance units : Watt/C
255  // Thermal conductance = 1 / Thermal resistance
256  //
257  // Thermal mass (or Thermal capicitance) : Energy required to
258  // raise temperature of object 1 degree.
259  // Thermal mass units : C/Joule
260  // Thermal mass = Thermal time constant / thermal resistance
261 
270 
271 
273  double winding_temperature_;
275  double housing_temperature_;
277  double ambient_temperature_;
278 
280  boost::mutex mutex_;
281 
283  bool overheat_;
284 
286  double heating_energy_sum_;
292  //double trace_sample_interval_;
295 
297  std::string actuator_name_;
298  std::string save_filename_;
299  std::string hwid_;
300 };
301 
302 
303 }; //end namepace ethercat_hardware
304 
305 #endif //ETHERCAT_HARDWARE__MOTOR_HEATING_MODEL_H
ethercat_hardware::MotorHeatingModel::startTemperaturePublisher
bool startTemperaturePublisher()
Definition: motor_heating_model.cpp:288
ethercat_hardware::MotorHeatingModelParametersEepromConfig::generateCRC
void generateCRC(void)
Definition: motor_heating_model.cpp:101
realtime_publisher.h
ethercat_hardware::MotorHeatingModel::getWindingTemperature
double getWindingTemperature()
Gets current winding temperature estimate (for testing)
Definition: motor_heating_model.h:220
ethercat_hardware::MotorHeatingModel::loadTemperatureState
bool loadTemperatureState()
Load saved temperature estimate from directory.
Definition: motor_heating_model.cpp:589
ethercat_hardware::MotorHeatingModelParameters
Definition: motor_heating_model.h:94
ethercat_hardware::MotorHeatingModelCommon::mutex_
boost::mutex mutex_
Lock around models list.
Definition: motor_heating_model.h:181
ethercat_hardware::MotorHeatingModelParametersEepromConfig::verifyCRC
bool verifyCRC(void) const
Definition: motor_heating_model.cpp:92
boost::shared_ptr< MotorHeatingModel >
ethercat_hardware::MotorHeatingModel::housing_to_ambient_thermal_conductance_
double housing_to_ambient_thermal_conductance_
Thermal conductance between motor housing and ambient : in Watt/C.
Definition: motor_heating_model.h:297
ethercat_hardware::MotorHeatingModelParameters::winding_thermal_time_constant_
double winding_thermal_time_constant_
Thermal time constant of motor winding : in seconds.
Definition: motor_heating_model.h:133
ethercat_hardware::MotorHeatingModelCommon::update_save_files_
bool update_save_files_
Definition: motor_heating_model.h:158
ethercat_hardware::MotorHeatingModel::hwid_
std::string hwid_
Hardware ID of device (ex. 680500501000)
Definition: motor_heating_model.h:331
ethercat_hardware::MotorHeatingModel::update
bool update(double heating_power, double ambient_temperature, double duration)
Updates motor temperature estimate.
Definition: motor_heating_model.cpp:343
ethercat_hardware::MotorHeatingModelCommon::enable_model_
bool enable_model_
If true, enables motor heating model. If false, motor heating model is run for any devices.
Definition: motor_heating_model.h:166
ethercat_hardware::MotorHeatingModel::save_filename_
std::string save_filename_
path to file where temperature data will be saved
Definition: motor_heating_model.h:330
ethercat_hardware::MotorHeatingModelParameters::max_winding_temperature_
double max_winding_temperature_
temperature limit of motor windings : in Celcius
Definition: motor_heating_model.h:137
ethercat_hardware::MotorHeatingModel::duration_since_last_sample_
double duration_since_last_sample_
Time (in seconds) since late sample interval occurred.
Definition: motor_heating_model.h:322
ethercat_hardware::MotorHeatingModelParametersEepromConfig::EEPROM_PAGE
static const unsigned EEPROM_PAGE
Definition: motor_heating_model.h:129
ethercat_hardware::MotorHeatingModelParametersEepromConfig::crc32_
uint32_t crc32_
CRC32 of first 256-4 bytes of structure.
Definition: motor_heating_model.h:127
ethercat_hardware::MotorHeatingModelCommon::attach
void attach(boost::shared_ptr< MotorHeatingModel > model)
Append model to list of models that need to have temperature data saved.
Definition: motor_heating_model.cpp:165
ethercat_hardware
Definition: motor_heating_model.h:53
ethercat_hardware::MotorHeatingModel::winding_thermal_mass_inverse_
double winding_thermal_mass_inverse_
Inverse of thermal mass for motor winding : in Joules/C.
Definition: motor_heating_model.h:299
ethercat_hardware::MotorHeatingModel::ambient_temperature_
double ambient_temperature_
Last recorded ambient temperature : in Celcius.
Definition: motor_heating_model.h:309
ethercat_hardware::MotorHeatingModelParametersEepromConfig::major_
uint16_t major_
Major revision of this structure.
Definition: motor_heating_model.h:121
ethercat_hardware::MotorHeatingModel::motor_params_
MotorHeatingModelParameters motor_params_
Definition: motor_heating_model.h:328
realtime_tools::RealtimePublisher< ethercat_hardware::MotorTemperature >
ethercat_hardware::MotorHeatingModel::winding_to_housing_thermal_conductance_
double winding_to_housing_thermal_conductance_
Thermal conductance between motor winding and housing : in Watt/C.
Definition: motor_heating_model.h:295
ethercat_hardware::MotorHeatingModelParametersEepromConfig::enforce_
bool enforce_
0 if heating model should be not be enforced, 0 otherwise
Definition: motor_heating_model.h:123
ethercat_hardware::MotorHeatingModelCommon::createSaveDirectory
bool createSaveDirectory()
Creates directory for saved motor heating information.
Definition: motor_heating_model.cpp:218
ethercat_hardware::MotorHeatingModelParametersEepromConfig::params_
MotorHeatingModelParameters params_
Motor parameters
Definition: motor_heating_model.h:125
ethercat_hardware::MotorHeatingModelCommon::load_save_files_
bool load_save_files_
If true, then class instances will attempt to load data from a saved temperature file.
Definition: motor_heating_model.h:162
ethercat_hardware::MotorHeatingModelParametersEepromConfig::pad2
uint8_t pad2[204]
Definition: motor_heating_model.h:126
ethercat_hardware::MotorHeatingModelCommon::models_
std::vector< boost::shared_ptr< MotorHeatingModel > > models_
List of MotorHeatingModels that need to have file data saved.
Definition: motor_heating_model.h:178
ethercat_hardware::MotorHeatingModelParameters::winding_to_housing_thermal_resistance_
double winding_to_housing_thermal_resistance_
Thermal resistance between motor winding and motor housing : in C/Watt.
Definition: motor_heating_model.h:131
ethercat_hardware::MotorHeatingModelParameters::housing_to_ambient_thermal_resistance_
double housing_to_ambient_thermal_resistance_
Thermal resistance between motor housing and ambient : in C/Watt.
Definition: motor_heating_model.h:129
ethercat_hardware::MotorHeatingModel::getHousingTemperature
double getHousingTemperature()
Gets current winding temperature estimate (for testing)
Definition: motor_heating_model.h:222
DiagnosticStatusWrapper.h
ethercat_hardware::MotorHeatingModel::hasOverheated
bool hasOverheated() const
Not thread save, should be called by same thread that calls update()
Definition: motor_heating_model.h:218
ethercat_hardware::MotorHeatingModelParametersEepromConfig::pad1
uint8_t pad1[3]
Definition: motor_heating_model.h:124
ethercat_hardware::MotorHeatingModel::updateFromDowntimeWithInterval
double updateFromDowntimeWithInterval(double downtime, double saved_ambient_temperature, double interval, unsigned cycles)
Updates estimated motor temperature for certain amount of downtime.
Definition: motor_heating_model.cpp:371
ethercat_hardware::MotorHeatingModelCommon::publish_temperature_
bool publish_temperature_
If true, each motor heating model with publish state information every 1 second.
Definition: motor_heating_model.h:168
ethercat_hardware::MotorHeatingModelCommon::disable_halt_
bool disable_halt_
Disables halting caused by a motor being overtemperature
Definition: motor_heating_model.h:164
ethercat_hardware::MotorHeatingModel::MotorHeatingModel
MotorHeatingModel(const MotorHeatingModelParameters &motor_params, const std::string &actuator_name, const std::string &hwid, const std::string &save_directory)
Constructor.
Definition: motor_heating_model.cpp:248
ethercat_hardware::MotorHeatingModelCommon::initialize
bool initialize()
Definition: motor_heating_model.cpp:174
ethercat_hardware::MotorHeatingModel
Definition: motor_heating_model.h:186
ethercat_hardware::MotorHeatingModelParametersEepromConfig::minor_
uint16_t minor_
Minor revision of this structure.
Definition: motor_heating_model.h:122
ethercat_hardware::MotorHeatingModel::ambient_temperature_sum_
double ambient_temperature_sum_
Sum of (abient heat * time) over last sample interval.
Definition: motor_heating_model.h:320
ethercat_hardware::MotorHeatingModel::mutex_
boost::mutex mutex_
mutex protects values updates by realtime thread and used by diagnostics thread
Definition: motor_heating_model.h:312
ethercat_hardware::MotorHeatingModel::saveTemperatureState
bool saveTemperatureState()
Definition: motor_heating_model.cpp:703
ethercat_hardware::MotorHeatingModel::calculateMotorHeatPower
double calculateMotorHeatPower(const ethercat_hardware::MotorTraceSample &sample, const ethercat_hardware::ActuatorInfo &actuator_info)
Definition: motor_heating_model.cpp:306
ethercat_hardware::MotorHeatingModelCommon
Definition: motor_heating_model.h:138
ethercat_hardware::MotorHeatingModel::publisher_
realtime_tools::RealtimePublisher< ethercat_hardware::MotorTemperature > * publisher_
Sample interval for trace (in seconds)
Definition: motor_heating_model.h:326
ethercat_hardware::__attribute__
ethercat_hardware::MotorHeatingModelCommon __attribute__
ethercat_hardware::MotorHeatingModel::heating_energy_sum_
double heating_energy_sum_
Sum of heat energy for last sample interval.
Definition: motor_heating_model.h:318
ethercat_hardware::MotorHeatingModel::reset
void reset()
Resets motor overheat flag.
Definition: motor_heating_model.cpp:422
ethercat_hardware::MotorHeatingModel::actuator_name_
std::string actuator_name_
name of actuator (ex. fl_caster_rotation_motor)
Definition: motor_heating_model.h:329
diagnostic_updater::DiagnosticStatusWrapper
ethercat_hardware::MotorHeatingModelCommon::saveThreadFunc
void saveThreadFunc()
Continuously saves motor heating model state.
Definition: motor_heating_model.cpp:192
ethercat_hardware::MotorHeatingModel::overheat_
bool overheat_
True if most has overheat, once set, will only clear when reset() is called.
Definition: motor_heating_model.h:315
ethercat_hardware::MotorHeatingModelCommon::MotorHeatingModelCommon
MotorHeatingModelCommon()
Constructor will use default settings for all parameters.
Definition: motor_heating_model.cpp:153
ethercat_hardware::MotorHeatingModel::diagnostics
void diagnostics(diagnostic_updater::DiagnosticStatusWrapper &d)
Appends heating diagnostic data to status wrapper.
Definition: motor_heating_model.cpp:431
ethercat_hardware::MotorHeatingModel::housing_thermal_mass_inverse_
double housing_thermal_mass_inverse_
Inverse of thermal mass for motor housing : in Joules/C.
Definition: motor_heating_model.h:301
ethercat_hardware::MotorHeatingModel::housing_temperature_
double housing_temperature_
Temperature estimate of motor housing : in Celcius.
Definition: motor_heating_model.h:307
ethercat_hardware::MotorHeatingModelCommon::save_thread_
boost::thread save_thread_
thread that will periodically save temperature data
Definition: motor_heating_model.h:174
ethercat_hardware::MotorHeatingModel::updateFromDowntime
void updateFromDowntime(double downtime, double saved_ambient_temperature)
Updates estimated motor temperature for long period of off-time.
Definition: motor_heating_model.cpp:395
ethercat_hardware::MotorHeatingModelParametersEepromConfig
Definition: motor_heating_model.h:119
ethercat_hardware::MotorHeatingModelParameters::housing_thermal_time_constant_
double housing_thermal_time_constant_
Thermal time constant of motor housing : in seconds.
Definition: motor_heating_model.h:135
ethercat_hardware::MotorHeatingModel::winding_temperature_
double winding_temperature_
Temperature estimate of motor winding : in Celcius.
Definition: motor_heating_model.h:305
ros::NodeHandle
ethercat_hardware::MotorHeatingModelCommon::save_directory_
std::string save_directory_
Directory where temperature save files should be put.
Definition: motor_heating_model.h:160


ethercat_hardware
Author(s): Rob Wheeler , Derek King
autogenerated on Sun Apr 2 2023 02:44:04