Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | List of all members
ethercat_hardware::MotorHeatingModelCommon Class Reference

#include <motor_heating_model.h>

Inheritance diagram for ethercat_hardware::MotorHeatingModelCommon:
Inheritance graph
[legend]

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 ()
 Constructor will use default settings for all parameters. More...
 
 MotorHeatingModelCommon (ros::NodeHandle nh)
 Constructor will read motor heating mode settings from node handle namespace
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...
 

Detailed Description

Definition at line 138 of file motor_heating_model.h.

Constructor & Destructor Documentation

◆ MotorHeatingModelCommon() [1/2]

ethercat_hardware::MotorHeatingModelCommon::MotorHeatingModelCommon ( ros::NodeHandle  nh)

Constructor will read motor heating mode settings from node handle namespace

Definition at line 110 of file motor_heating_model.cpp.

◆ MotorHeatingModelCommon() [2/2]

ethercat_hardware::MotorHeatingModelCommon::MotorHeatingModelCommon ( )

Constructor will use default settings for all parameters.

Definition at line 153 of file motor_heating_model.cpp.

Member Function Documentation

◆ attach()

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 165 of file motor_heating_model.cpp.

◆ createSaveDirectory()

bool ethercat_hardware::MotorHeatingModelCommon::createSaveDirectory ( )
protected

Creates directory for saved motor heating information.

Definition at line 218 of file motor_heating_model.cpp.

◆ initialize()

bool ethercat_hardware::MotorHeatingModelCommon::initialize ( )

Definition at line 174 of file motor_heating_model.cpp.

◆ saveThreadFunc()

void ethercat_hardware::MotorHeatingModelCommon::saveThreadFunc ( )
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 192 of file motor_heating_model.cpp.

Member Data Documentation

◆ disable_halt_

bool ethercat_hardware::MotorHeatingModelCommon::disable_halt_

Disables halting caused by a motor being overtemperature

Definition at line 164 of file motor_heating_model.h.

◆ enable_model_

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 166 of file motor_heating_model.h.

◆ load_save_files_

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 162 of file motor_heating_model.h.

◆ models_

std::vector< boost::shared_ptr<MotorHeatingModel> > ethercat_hardware::MotorHeatingModelCommon::models_
protected

List of MotorHeatingModels that need to have file data saved.

Definition at line 178 of file motor_heating_model.h.

◆ mutex_

boost::mutex ethercat_hardware::MotorHeatingModelCommon::mutex_
protected

Lock around models list.

Definition at line 181 of file motor_heating_model.h.

◆ publish_temperature_

bool ethercat_hardware::MotorHeatingModelCommon::publish_temperature_

If true, each motor heating model with publish state information every 1 second.

Definition at line 168 of file motor_heating_model.h.

◆ save_directory_

std::string ethercat_hardware::MotorHeatingModelCommon::save_directory_

Directory where temperature save files should be put.

Definition at line 160 of file motor_heating_model.h.

◆ save_thread_

boost::thread ethercat_hardware::MotorHeatingModelCommon::save_thread_
protected

thread that will periodically save temperature data

Definition at line 174 of file motor_heating_model.h.

◆ update_save_files_

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 158 of file motor_heating_model.h.


The documentation for this class was generated from the following files:


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