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/shared_ptr.hpp>
48 
49 #include <vector>
50 #include <string>
51 
53 {
54 
55 
62 {
73 } __attribute__ ((__packed__));
74 
75 
87 {
88  uint16_t major_;
89  uint16_t minor_;
90  bool enforce_;
91  uint8_t pad1[3];
93  uint8_t pad2[204];
94  uint32_t crc32_;
95 
96  static const unsigned EEPROM_PAGE = 4093; // Acutator info on page 4095, MCB config on 4094
97 
98  bool verifyCRC(void) const;
99  void generateCRC(void);
100 } __attribute__ ((__packed__));
101 
102 
103 class MotorHeatingModel;
104 
105 class MotorHeatingModelCommon : private boost::noncopyable
106 {
107 public:
110  MotorHeatingModelCommon(ros::NodeHandle nh);
111 
114  MotorHeatingModelCommon();
115 
116 
117  bool initialize();
118 
121  void attach(boost::shared_ptr<MotorHeatingModel> model);
122 
127  std::string save_directory_;
136 
137 protected:
138  bool createSaveDirectory();
139 
141  boost::thread save_thread_;
142  void saveThreadFunc();
143 
145  std::vector< boost::shared_ptr<MotorHeatingModel> > models_;
146 
148  boost::mutex mutex_;
149 };
150 
151 
152 
153 class MotorHeatingModel : private boost::noncopyable
154 {
155 public:
156 
158  const std::string &actuator_name,
159  const std::string &hwid,
160  const std::string &save_directory
161  );
162 
163  bool startTemperaturePublisher();
164 
175  bool update(double heating_power, double ambient_temperature, double duration);
176  bool update(const ethercat_hardware::MotorTraceSample &sample,
177  const ethercat_hardware::ActuatorInfo &actuator_info,
178  double ambient_temperature, double duration)
179  {
180  double heating_power = calculateMotorHeatPower(sample, actuator_info);
181  return update(heating_power, ambient_temperature, duration);
182  }
183 
185  bool hasOverheated() const {return overheat_;}
187  double getWindingTemperature() {return winding_temperature_;}
189  double getHousingTemperature() {return housing_temperature_;}
190 
191 
193  void reset();
194 
195 
207  void updateFromDowntime(double downtime, double saved_ambient_temperature);
208 
209 
217  double updateFromDowntimeWithInterval(double downtime,
218  double saved_ambient_temperature,
219  double interval,
220  unsigned cycles);
221 
222 
225  double calculateMotorHeatPower(const ethercat_hardware::MotorTraceSample &sample,
226  const ethercat_hardware::ActuatorInfo &actuator_info);
227 
228 
230  bool loadTemperatureState();
231 
232 
238  bool saveTemperatureState();
239 
240 
243 
244 
245 
246 
247 protected:
248  // Following values are calculated from motor parameters.
249  // They are more useful when peforming motor model calculations
250  //
251  // Thermal is conducance amount of heat power tranfered for a
252  // given temperature differential
253  // Thermal conductance units : Watt/C
254  // Thermal conductance = 1 / Thermal resistance
255  //
256  // Thermal mass (or Thermal capicitance) : Energy required to
257  // raise temperature of object 1 degree.
258  // Thermal mass units : C/Joule
259  // Thermal mass = Thermal time constant / thermal resistance
260 
269 
270 
277 
279  boost::mutex mutex_;
280 
282  bool overheat_;
283 
291  //double trace_sample_interval_;
294 
296  std::string actuator_name_;
297  std::string save_filename_;
298  std::string hwid_;
299 };
300 
301 
302 }; //end namepace ethercat_hardware
303 
304 #endif //ETHERCAT_HARDWARE__MOTOR_HEATING_MODEL_H
d
uint16_t major_
Major revision of this structure.
MotorHeatingModelParameters params_
Motor parameters.
double winding_thermal_time_constant_
Thermal time constant of motor winding : in seconds.
bool update(const ethercat_hardware::MotorTraceSample &sample, const ethercat_hardware::ActuatorInfo &actuator_info, double ambient_temperature, double duration)
bool hasOverheated() const
Not thread save, should be called by same thread that calls update()
bool enable_model_
If true, enables motor heating model. If false, motor heating model is run for any devices...
std::string save_filename_
path to file where temperature data will be saved
ROSCONSOLE_DECL void initialize()
bool disable_halt_
Disables halting caused by a motor being overtemperature.
bool overheat_
True if most has overheat, once set, will only clear when reset() is called.
double getWindingTemperature()
Gets current winding temperature estimate (for testing)
bool enforce_
0 if heating model should be not be enforced, 0 otherwise
double heating_energy_sum_
Sum of heat energy for last sample interval.
uint16_t minor_
Minor revision of this structure.
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
std::string save_directory_
Directory where temperature save files should be put.
boost::mutex mutex_
Lock around models list.
double winding_to_housing_thermal_resistance_
Thermal resistance between motor winding and motor housing : in C/Watt.
bool load_save_files_
If true, then class instances will attempt to load data from a saved temperature file.
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.
static const unsigned EEPROM_PAGE
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)
double housing_thermal_time_constant_
Thermal time constant of motor housing : in seconds.
double winding_temperature_
Temperature estimate of motor winding : in Celcius.
uint8_t pad2[204]
double max_winding_temperature_
temperature limit of motor windings : in Celcius
double housing_to_ambient_thermal_conductance_
Thermal conductance between motor housing and ambient : in Watt/C.
uint8_t pad1[3]
double housing_thermal_mass_inverse_
Inverse of thermal mass for motor housing : in Joules/C.
bool publish_temperature_
If true, each motor heating model with publish state information every 1 second.
double ambient_temperature_
Last recorded ambient temperature : in Celcius.
double winding_to_housing_thermal_conductance_
Thermal conductance between motor winding and housing : in Watt/C.
void generateCRC(void)
double getHousingTemperature()
Gets current winding temperature estimate (for testing)
double housing_to_ambient_thermal_resistance_
Thermal resistance between motor housing and ambient : in C/Watt.
bool verifyCRC(void) const
ethercat_hardware::MotorHeatingModelCommon __attribute__
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.
std::string hwid_
Hardware ID of device (ex. 680500501000)


ethercat_hardware
Author(s): Rob Wheeler , Derek King
autogenerated on Fri Mar 15 2019 02:53:29