Public Types | Public Member Functions | List of all members
canopen::HandleLayerBase Class Referenceabstract

#include <handle_layer_base.h>

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

Public Types

enum  CanSwitchResult { NotSupported, NotReadyToSwitch, ReadyToSwitch, NoNeedToSwitch }
 
- Public Types inherited from canopen::Layer
enum  LayerState
 

Public Member Functions

virtual CanSwitchResult canSwitch (const canopen::MotorBase::OperationMode &m)=0
 
virtual void enableLimits (bool enable)=0
 
virtual void enforceLimits (const ros::Duration &period, bool reset)=0
 
virtual bool forwardForMode (const canopen::MotorBase::OperationMode &m)=0
 
 HandleLayerBase (const std::string &name)
 
virtual void registerHandle (hardware_interface::JointStateInterface &iface)=0
 
virtual hardware_interface::JointHandleregisterHandle (hardware_interface::PositionJointInterface &iface, const joint_limits_interface::JointLimits &limits, const joint_limits_interface::SoftJointLimits *soft_limits=0)=0
 
virtual hardware_interface::JointHandleregisterHandle (hardware_interface::VelocityJointInterface &iface, const joint_limits_interface::JointLimits &limits, const joint_limits_interface::SoftJointLimits *soft_limits=0)=0
 
virtual hardware_interface::JointHandleregisterHandle (hardware_interface::EffortJointInterface &iface, const joint_limits_interface::JointLimits &limits, const joint_limits_interface::SoftJointLimits *soft_limits=0)=0
 
virtual bool switchMode (const canopen::MotorBase::OperationMode &m)=0
 
- 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 ()
 

Additional Inherited Members

- Public Attributes inherited from canopen::Layer
 Error
 
 Halt
 
 Init
 
const std::string name
 
 Off
 
 Ready
 
 Recover
 
 Shutdown
 
- Protected Member Functions inherited from canopen::Layer
virtual void handleDiag (LayerReport &report)=0
 
virtual void handleHalt (LayerStatus &status)=0
 
virtual void handleInit (LayerStatus &status)=0
 
virtual void handleRead (LayerStatus &status, const LayerState &current_state)=0
 
virtual void handleRecover (LayerStatus &status)=0
 
virtual void handleShutdown (LayerStatus &status)=0
 
virtual void handleWrite (LayerStatus &status, const LayerState &current_state)=0
 

Detailed Description

Definition at line 10 of file handle_layer_base.h.

Member Enumeration Documentation

Enumerator
NotSupported 
NotReadyToSwitch 
ReadyToSwitch 
NoNeedToSwitch 

Definition at line 14 of file handle_layer_base.h.

Constructor & Destructor Documentation

canopen::HandleLayerBase::HandleLayerBase ( const std::string &  name)
inline

Definition at line 12 of file handle_layer_base.h.

Member Function Documentation

virtual CanSwitchResult canopen::HandleLayerBase::canSwitch ( const canopen::MotorBase::OperationMode m)
pure virtual

Implemented in canopen::HandleLayer.

virtual void canopen::HandleLayerBase::enableLimits ( bool  enable)
pure virtual

Implemented in canopen::HandleLayer.

virtual void canopen::HandleLayerBase::enforceLimits ( const ros::Duration period,
bool  reset 
)
pure virtual

Implemented in canopen::HandleLayer.

virtual bool canopen::HandleLayerBase::forwardForMode ( const canopen::MotorBase::OperationMode m)
pure virtual

Implemented in canopen::HandleLayer.

virtual void canopen::HandleLayerBase::registerHandle ( hardware_interface::JointStateInterface iface)
pure virtual

Implemented in canopen::HandleLayer.

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

Implemented in canopen::HandleLayer.

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

Implemented in canopen::HandleLayer.

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

Implemented in canopen::HandleLayer.

virtual bool canopen::HandleLayerBase::switchMode ( const canopen::MotorBase::OperationMode m)
pure virtual

Implemented in canopen::HandleLayer.


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


canopen_motor_node
Author(s): Mathias Lüdtke
autogenerated on Sat May 4 2019 02:40:47