Public Member Functions | Static Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
canopen::HandleLayer Class Reference

#include <handle_layer.h>

Inheritance diagram for canopen::HandleLayer:
Inheritance graph
[legend]

Public Member Functions

CanSwitchResult canSwitch (const canopen::MotorBase::OperationMode &m)
 
void enableLimits (bool enable)
 
void enforceLimits (const ros::Duration &period, bool reset)
 
bool forwardForMode (const canopen::MotorBase::OperationMode &m)
 
 HandleLayer (const std::string &name, const canopen::MotorBaseSharedPtr &motor, const canopen::ObjectStorageSharedPtr storage, XmlRpc::XmlRpcValue &options)
 
bool prepareFilters (canopen::LayerStatus &status)
 
void registerHandle (hardware_interface::JointStateInterface &iface)
 
hardware_interface::JointHandleregisterHandle (hardware_interface::PositionJointInterface &iface, const joint_limits_interface::JointLimits &limits, const joint_limits_interface::SoftJointLimits *soft_limits=0)
 
hardware_interface::JointHandleregisterHandle (hardware_interface::VelocityJointInterface &iface, const joint_limits_interface::JointLimits &limits, const joint_limits_interface::SoftJointLimits *soft_limits=0)
 
hardware_interface::JointHandleregisterHandle (hardware_interface::EffortJointInterface &iface, const joint_limits_interface::JointLimits &limits, const joint_limits_interface::SoftJointLimits *soft_limits=0)
 
bool switchMode (const canopen::MotorBase::OperationMode &m)
 
- Public Member Functions inherited from canopen::HandleLayerBase
 HandleLayerBase (const std::string &name)
 
- Public Member Functions inherited from canopen::Layer
void diag (LayerReport &report)
 
LayerState getLayerState ()
 
void halt (LayerStatus &status)
 
void init (LayerStatus &status)
 
 Layer (const std::string &n)
 
void read (LayerStatus &status)
 
void recover (LayerStatus &status)
 
void shutdown (LayerStatus &status)
 
void write (LayerStatus &status)
 
virtual ~Layer ()
 

Static Public Member Functions

static double * assignVariable (const std::string &name, double *ptr, const std::string &req)
 

Private Types

typedef boost::unordered_map< MotorBase::OperationMode, hardware_interface::JointHandle * > CommandMap
 

Private Member Functions

template<typename T >
hardware_interface::JointHandleaddHandle (T &iface, hardware_interface::JointHandle *jh, const std::vector< MotorBase::OperationMode > &modes)
 
virtual void handleDiag (canopen::LayerReport &report)
 
virtual void handleHalt (canopen::LayerStatus &status)
 
virtual void handleInit (canopen::LayerStatus &status)
 
virtual void handleRead (canopen::LayerStatus &status, const LayerState &current_state)
 
virtual void handleRecover (canopen::LayerStatus &status)
 
virtual void handleShutdown (canopen::LayerStatus &status)
 
virtual void handleWrite (canopen::LayerStatus &status, const LayerState &current_state)
 
bool select (const canopen::MotorBase::OperationMode &m)
 

Private Attributes

double cmd_eff_
 
double cmd_pos_
 
double cmd_vel_
 
CommandMap commands_
 
boost::scoped_ptr< UnitConverterconv_eff_
 
boost::scoped_ptr< UnitConverterconv_pos_
 
boost::scoped_ptr< UnitConverterconv_target_eff_
 
boost::scoped_ptr< UnitConverterconv_target_pos_
 
boost::scoped_ptr< UnitConverterconv_target_vel_
 
boost::scoped_ptr< UnitConverterconv_vel_
 
double eff_
 
bool enable_limits_
 
filters::FilterChain< double > filter_eff_
 
filters::FilterChain< double > filter_pos_
 
filters::FilterChain< double > filter_vel_
 
boost::atomic< bool > forward_command_
 
hardware_interface::JointHandle jeh_
 
boost::atomic< hardware_interface::JointHandle * > jh_
 
hardware_interface::JointHandle jph_
 
hardware_interface::JointStateHandle jsh_
 
hardware_interface::JointHandle jvh_
 
std::vector< LimitsHandleBaseSharedPtrlimits_
 
canopen::MotorBaseSharedPtr motor_
 
XmlRpc::XmlRpcValue options_
 
double pos_
 
ObjectVariables variables_
 
double vel_
 

Additional Inherited Members

- Public Types inherited from canopen::HandleLayerBase
enum  CanSwitchResult { NotSupported, NotReadyToSwitch, ReadyToSwitch, NoNeedToSwitch }
 
- Public Types inherited from canopen::Layer
enum  LayerState
 
- Public Attributes inherited from canopen::Layer
 Error
 
 Halt
 
 Init
 
const std::string name
 
 Off
 
 Ready
 
 Recover
 
 Shutdown
 

Detailed Description

Definition at line 84 of file handle_layer.h.

Member Typedef Documentation

Definition at line 102 of file handle_layer.h.

Constructor & Destructor Documentation

HandleLayer::HandleLayer ( const std::string &  name,
const canopen::MotorBaseSharedPtr motor,
const canopen::ObjectStorageSharedPtr  storage,
XmlRpc::XmlRpcValue options 
)

Definition at line 26 of file handle_layer.cpp.

Member Function Documentation

template<typename T >
hardware_interface::JointHandle* canopen::HandleLayer::addHandle ( T &  iface,
hardware_interface::JointHandle jh,
const std::vector< MotorBase::OperationMode > &  modes 
)
inlineprivate

Definition at line 105 of file handle_layer.h.

static double* canopen::HandleLayer::assignVariable ( const std::string &  name,
double *  ptr,
const std::string &  req 
)
inlinestatic

Definition at line 129 of file handle_layer.h.

HandleLayer::CanSwitchResult HandleLayer::canSwitch ( const canopen::MotorBase::OperationMode m)
virtual

Implements canopen::HandleLayerBase.

Definition at line 59 of file handle_layer.cpp.

void HandleLayer::enableLimits ( bool  enable)
virtual

Implements canopen::HandleLayerBase.

Definition at line 213 of file handle_layer.cpp.

void HandleLayer::enforceLimits ( const ros::Duration period,
bool  reset 
)
virtual

Implements canopen::HandleLayerBase.

Definition at line 206 of file handle_layer.cpp.

bool HandleLayer::forwardForMode ( const canopen::MotorBase::OperationMode m)
virtual

Implements canopen::HandleLayerBase.

Definition at line 85 of file handle_layer.cpp.

virtual void canopen::HandleLayer::handleDiag ( canopen::LayerReport report)
inlineprivatevirtual

Implements canopen::Layer.

Definition at line 157 of file handle_layer.h.

virtual void canopen::HandleLayer::handleHalt ( canopen::LayerStatus status)
inlineprivatevirtual

Implements canopen::Layer.

Definition at line 159 of file handle_layer.h.

void HandleLayer::handleInit ( canopen::LayerStatus status)
privatevirtual

Implements canopen::Layer.

Definition at line 190 of file handle_layer.cpp.

void HandleLayer::handleRead ( canopen::LayerStatus status,
const LayerState current_state 
)
privatevirtual

Implements canopen::Layer.

Definition at line 138 of file handle_layer.cpp.

virtual void canopen::HandleLayer::handleRecover ( canopen::LayerStatus status)
inlineprivatevirtual

Implements canopen::Layer.

Definition at line 160 of file handle_layer.h.

virtual void canopen::HandleLayer::handleShutdown ( canopen::LayerStatus status)
inlineprivatevirtual

Implements canopen::Layer.

Definition at line 158 of file handle_layer.h.

void HandleLayer::handleWrite ( canopen::LayerStatus status,
const LayerState current_state 
)
privatevirtual

Implements canopen::Layer.

Definition at line 146 of file handle_layer.cpp.

bool HandleLayer::prepareFilters ( canopen::LayerStatus status)

Definition at line 184 of file handle_layer.cpp.

void canopen::HandleLayer::registerHandle ( hardware_interface::JointStateInterface iface)
inlinevirtual

Implements canopen::HandleLayerBase.

Definition at line 135 of file handle_layer.h.

hardware_interface::JointHandle * HandleLayer::registerHandle ( hardware_interface::PositionJointInterface iface,
const joint_limits_interface::JointLimits limits,
const joint_limits_interface::SoftJointLimits soft_limits = 0 
)
virtual

Implements canopen::HandleLayerBase.

Definition at line 99 of file handle_layer.cpp.

hardware_interface::JointHandle * HandleLayer::registerHandle ( hardware_interface::VelocityJointInterface iface,
const joint_limits_interface::JointLimits limits,
const joint_limits_interface::SoftJointLimits soft_limits = 0 
)
virtual

Implements canopen::HandleLayerBase.

Definition at line 112 of file handle_layer.cpp.

hardware_interface::JointHandle * HandleLayer::registerHandle ( hardware_interface::EffortJointInterface iface,
const joint_limits_interface::JointLimits limits,
const joint_limits_interface::SoftJointLimits soft_limits = 0 
)
virtual

Implements canopen::HandleLayerBase.

Definition at line 125 of file handle_layer.cpp.

bool HandleLayer::select ( const canopen::MotorBase::OperationMode m)
private

Definition at line 19 of file handle_layer.cpp.

bool HandleLayer::switchMode ( const canopen::MotorBase::OperationMode m)
virtual

Implements canopen::HandleLayerBase.

Definition at line 71 of file handle_layer.cpp.

Member Data Documentation

double canopen::HandleLayer::cmd_eff_
private

Definition at line 88 of file handle_layer.h.

double canopen::HandleLayer::cmd_pos_
private

Definition at line 88 of file handle_layer.h.

double canopen::HandleLayer::cmd_vel_
private

Definition at line 88 of file handle_layer.h.

CommandMap canopen::HandleLayer::commands_
private

Definition at line 103 of file handle_layer.h.

boost::scoped_ptr<UnitConverter> canopen::HandleLayer::conv_eff_
private

Definition at line 92 of file handle_layer.h.

boost::scoped_ptr<UnitConverter> canopen::HandleLayer::conv_pos_
private

Definition at line 92 of file handle_layer.h.

boost::scoped_ptr<UnitConverter> canopen::HandleLayer::conv_target_eff_
private

Definition at line 91 of file handle_layer.h.

boost::scoped_ptr<UnitConverter> canopen::HandleLayer::conv_target_pos_
private

Definition at line 91 of file handle_layer.h.

boost::scoped_ptr<UnitConverter> canopen::HandleLayer::conv_target_vel_
private

Definition at line 91 of file handle_layer.h.

boost::scoped_ptr<UnitConverter> canopen::HandleLayer::conv_vel_
private

Definition at line 92 of file handle_layer.h.

double canopen::HandleLayer::eff_
private

Definition at line 86 of file handle_layer.h.

bool canopen::HandleLayer::enable_limits_
private

Definition at line 126 of file handle_layer.h.

filters::FilterChain<double> canopen::HandleLayer::filter_eff_
private

Definition at line 94 of file handle_layer.h.

filters::FilterChain<double> canopen::HandleLayer::filter_pos_
private

Definition at line 94 of file handle_layer.h.

filters::FilterChain<double> canopen::HandleLayer::filter_vel_
private

Definition at line 94 of file handle_layer.h.

boost::atomic<bool> canopen::HandleLayer::forward_command_
private

Definition at line 100 of file handle_layer.h.

hardware_interface::JointHandle canopen::HandleLayer::jeh_
private

Definition at line 98 of file handle_layer.h.

boost::atomic<hardware_interface::JointHandle*> canopen::HandleLayer::jh_
private

Definition at line 99 of file handle_layer.h.

hardware_interface::JointHandle canopen::HandleLayer::jph_
private

Definition at line 98 of file handle_layer.h.

hardware_interface::JointStateHandle canopen::HandleLayer::jsh_
private

Definition at line 97 of file handle_layer.h.

hardware_interface::JointHandle canopen::HandleLayer::jvh_
private

Definition at line 98 of file handle_layer.h.

std::vector<LimitsHandleBaseSharedPtr> canopen::HandleLayer::limits_
private

Definition at line 125 of file handle_layer.h.

canopen::MotorBaseSharedPtr canopen::HandleLayer::motor_
private

Definition at line 85 of file handle_layer.h.

XmlRpc::XmlRpcValue canopen::HandleLayer::options_
private

Definition at line 95 of file handle_layer.h.

double canopen::HandleLayer::pos_
private

Definition at line 86 of file handle_layer.h.

ObjectVariables canopen::HandleLayer::variables_
private

Definition at line 90 of file handle_layer.h.

double canopen::HandleLayer::vel_
private

Definition at line 86 of file handle_layer.h.


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


canopen_motor_node
Author(s): Mathias Lüdtke
autogenerated on Fri May 14 2021 02:59:45