35 #ifndef ETHERCAT_HARDWARE__MOTOR_HEATING_MODEL_H 36 #define ETHERCAT_HARDWARE__MOTOR_HEATING_MODEL_H 38 #include "ethercat_hardware/MotorTemperature.h" 39 #include "ethercat_hardware/MotorTraceSample.h" 40 #include "ethercat_hardware/ActuatorInfo.h" 45 #include <boost/utility.hpp> 46 #include <boost/thread/mutex.hpp> 47 #include <boost/thread/thread.hpp> 48 #include <boost/shared_ptr.hpp> 106 class MotorHeatingModelCommon :
private boost::noncopyable
115 MotorHeatingModelCommon();
139 bool createSaveDirectory();
143 void saveThreadFunc();
146 std::vector< boost::shared_ptr<MotorHeatingModel> >
models_;
159 const std::string &actuator_name,
160 const std::string &hwid,
161 const std::string &save_directory
164 bool startTemperaturePublisher();
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)
181 double heating_power = calculateMotorHeatPower(sample, actuator_info);
182 return update(heating_power, ambient_temperature, duration);
208 void updateFromDowntime(
double downtime,
double saved_ambient_temperature);
218 double updateFromDowntimeWithInterval(
double downtime,
219 double saved_ambient_temperature,
226 double calculateMotorHeatPower(
const ethercat_hardware::MotorTraceSample &sample,
227 const ethercat_hardware::ActuatorInfo &actuator_info);
231 bool loadTemperatureState();
239 bool saveTemperatureState();
305 #endif //ETHERCAT_HARDWARE__MOTOR_HEATING_MODEL_H
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.
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.
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.
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)