#include <motor_heating_model.h>
Public Member Functions | |
void | attach (boost::shared_ptr< MotorHeatingModel > model) |
Append model to list of models that need to have temperature data saved. More... | |
bool | initialize () |
MotorHeatingModelCommon (ros::NodeHandle nh) | |
Constructor will read motor heating mode settings from node handle namespace. More... | |
MotorHeatingModelCommon () | |
Constructor will use default settings for all parameters. More... | |
Public Attributes | |
bool | disable_halt_ |
Disables halting caused by a motor being overtemperature. More... | |
bool | enable_model_ |
If true, enables motor heating model. If false, motor heating model is run for any devices. More... | |
bool | load_save_files_ |
If true, then class instances will attempt to load data from a saved temperature file. More... | |
bool | publish_temperature_ |
If true, each motor heating model with publish state information every 1 second. More... | |
std::string | save_directory_ |
Directory where temperature save files should be put. More... | |
bool | update_save_files_ |
Protected Member Functions | |
bool | createSaveDirectory () |
Creates directory for saved motor heating information. More... | |
void | saveThreadFunc () |
Continuously saves motor heating model state. More... | |
Protected Attributes | |
std::vector< boost::shared_ptr< MotorHeatingModel > > | models_ |
List of MotorHeatingModels that need to have file data saved. More... | |
boost::mutex | mutex_ |
Lock around models list. More... | |
boost::thread | save_thread_ |
thread that will periodically save temperature data More... | |
Definition at line 106 of file motor_heating_model.h.
ethercat_hardware::MotorHeatingModelCommon::MotorHeatingModelCommon | ( | ros::NodeHandle | nh | ) |
Constructor will read motor heating mode settings from node handle namespace.
Definition at line 78 of file motor_heating_model.cpp.
ethercat_hardware::MotorHeatingModelCommon::MotorHeatingModelCommon | ( | ) |
Constructor will use default settings for all parameters.
Definition at line 121 of file motor_heating_model.cpp.
void ethercat_hardware::MotorHeatingModelCommon::attach | ( | boost::shared_ptr< MotorHeatingModel > | model | ) |
Append model to list of models that need to have temperature data saved.
!
Definition at line 133 of file motor_heating_model.cpp.
|
protected |
Creates directory for saved motor heating information.
Definition at line 186 of file motor_heating_model.cpp.
bool ethercat_hardware::MotorHeatingModelCommon::initialize | ( | ) |
Definition at line 142 of file motor_heating_model.cpp.
|
protected |
Continuously saves motor heating model state.
Continuously saved motor state information so state of all registered motor heating model objects. This function is run in its own thread so the saveTemperatureState() funcion of each MotorHeatingModel object should perform appropriate locking.
Definition at line 160 of file motor_heating_model.cpp.
bool ethercat_hardware::MotorHeatingModelCommon::disable_halt_ |
Disables halting caused by a motor being overtemperature.
Definition at line 132 of file motor_heating_model.h.
bool ethercat_hardware::MotorHeatingModelCommon::enable_model_ |
If true, enables motor heating model. If false, motor heating model is run for any devices.
Definition at line 134 of file motor_heating_model.h.
bool ethercat_hardware::MotorHeatingModelCommon::load_save_files_ |
If true, then class instances will attempt to load data from a saved temperature file.
Definition at line 130 of file motor_heating_model.h.
|
protected |
List of MotorHeatingModels that need to have file data saved.
Definition at line 146 of file motor_heating_model.h.
|
protected |
Lock around models list.
Definition at line 149 of file motor_heating_model.h.
bool ethercat_hardware::MotorHeatingModelCommon::publish_temperature_ |
If true, each motor heating model with publish state information every 1 second.
Definition at line 136 of file motor_heating_model.h.
std::string ethercat_hardware::MotorHeatingModelCommon::save_directory_ |
Directory where temperature save files should be put.
Definition at line 128 of file motor_heating_model.h.
|
protected |
thread that will periodically save temperature data
Definition at line 142 of file motor_heating_model.h.
bool ethercat_hardware::MotorHeatingModelCommon::update_save_files_ |
Directory where motor model haeting data will be saved. Defaults to /var/lib/motor_heating_model If true, then temeperature data to will be periodically saved to file
Definition at line 126 of file motor_heating_model.h.