Public Types | Public Member Functions
canopen::HandleLayerBase Class Reference

#include <handle_layer_base.h>

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

List of all members.

Public Types

enum  CanSwitchResult { NotSupported, NotReadyToSwitch, ReadyToSwitch, NoNeedToSwitch }

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::JointHandle
registerHandle (hardware_interface::PositionJointInterface &iface, const joint_limits_interface::JointLimits &limits, const joint_limits_interface::SoftJointLimits *soft_limits=0)=0
virtual
hardware_interface::JointHandle
registerHandle (hardware_interface::VelocityJointInterface &iface, const joint_limits_interface::JointLimits &limits, const joint_limits_interface::SoftJointLimits *soft_limits=0)=0
virtual
hardware_interface::JointHandle
registerHandle (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

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

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.

Implemented in canopen::HandleLayer.

Implemented in canopen::HandleLayer.

Implemented in canopen::HandleLayer.

Implemented in canopen::HandleLayer.

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 Sun Sep 3 2017 03:10:55