Go to the documentation of this file.
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>
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
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)
182 return update(heating_power, ambient_temperature, duration);
219 double saved_ambient_temperature,
227 const ethercat_hardware::ActuatorInfo &actuator_info);
305 #endif //ETHERCAT_HARDWARE__MOTOR_HEATING_MODEL_H
bool startTemperaturePublisher()
double getWindingTemperature()
Gets current winding temperature estimate (for testing)
bool loadTemperatureState()
Load saved temperature estimate from directory.
boost::mutex mutex_
Lock around models list.
bool verifyCRC(void) const
double housing_to_ambient_thermal_conductance_
Thermal conductance between motor housing and ambient : in Watt/C.
double winding_thermal_time_constant_
Thermal time constant of motor winding : in seconds.
std::string hwid_
Hardware ID of device (ex. 680500501000)
bool update(double heating_power, double ambient_temperature, double duration)
Updates motor temperature estimate.
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
double max_winding_temperature_
temperature limit of motor windings : in Celcius
double duration_since_last_sample_
Time (in seconds) since late sample interval occurred.
static const unsigned EEPROM_PAGE
uint32_t crc32_
CRC32 of first 256-4 bytes of structure.
void attach(boost::shared_ptr< MotorHeatingModel > model)
Append model to list of models that need to have temperature data saved.
double winding_thermal_mass_inverse_
Inverse of thermal mass for motor winding : in Joules/C.
double ambient_temperature_
Last recorded ambient temperature : in Celcius.
uint16_t major_
Major revision of this structure.
MotorHeatingModelParameters motor_params_
double winding_to_housing_thermal_conductance_
Thermal conductance between motor winding and housing : in Watt/C.
bool enforce_
0 if heating model should be not be enforced, 0 otherwise
bool createSaveDirectory()
Creates directory for saved motor heating information.
MotorHeatingModelParameters params_
Motor parameters
bool load_save_files_
If true, then class instances will attempt to load data from a saved temperature file.
std::vector< boost::shared_ptr< MotorHeatingModel > > models_
List of MotorHeatingModels that need to have file data saved.
double winding_to_housing_thermal_resistance_
Thermal resistance between motor winding and motor housing : in C/Watt.
double housing_to_ambient_thermal_resistance_
Thermal resistance between motor housing and ambient : in C/Watt.
double getHousingTemperature()
Gets current winding temperature estimate (for testing)
bool hasOverheated() const
Not thread save, should be called by same thread that calls update()
double updateFromDowntimeWithInterval(double downtime, double saved_ambient_temperature, double interval, unsigned cycles)
Updates estimated motor temperature for certain amount of downtime.
bool publish_temperature_
If true, each motor heating model with publish state information every 1 second.
bool disable_halt_
Disables halting caused by a motor being overtemperature
MotorHeatingModel(const MotorHeatingModelParameters &motor_params, const std::string &actuator_name, const std::string &hwid, const std::string &save_directory)
Constructor.
uint16_t minor_
Minor revision of this structure.
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
bool saveTemperatureState()
double calculateMotorHeatPower(const ethercat_hardware::MotorTraceSample &sample, const ethercat_hardware::ActuatorInfo &actuator_info)
realtime_tools::RealtimePublisher< ethercat_hardware::MotorTemperature > * publisher_
Sample interval for trace (in seconds)
ethercat_hardware::MotorHeatingModelCommon __attribute__
double heating_energy_sum_
Sum of heat energy for last sample interval.
void reset()
Resets motor overheat flag.
std::string actuator_name_
name of actuator (ex. fl_caster_rotation_motor)
void saveThreadFunc()
Continuously saves motor heating model state.
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.
void diagnostics(diagnostic_updater::DiagnosticStatusWrapper &d)
Appends heating diagnostic data to status wrapper.
double housing_thermal_mass_inverse_
Inverse of thermal mass for motor housing : in Joules/C.
double housing_temperature_
Temperature estimate of motor housing : in Celcius.
boost::thread save_thread_
thread that will periodically save temperature data
void updateFromDowntime(double downtime, double saved_ambient_temperature)
Updates estimated motor temperature for long period of off-time.
double housing_thermal_time_constant_
Thermal time constant of motor housing : in seconds.
double winding_temperature_
Temperature estimate of motor winding : in Celcius.
std::string save_directory_
Directory where temperature save files should be put.
ethercat_hardware
Author(s): Rob Wheeler
, Derek King
autogenerated on Thu Sep 26 2024 02:44:04