handle_layer_base.h
Go to the documentation of this file.
00001 
00002 #ifndef CANOPEN_MOTOR_NODE_HANDLE_LAYER_BASE_H_
00003 #define CANOPEN_MOTOR_NODE_HANDLE_LAYER_BASE_H_
00004 
00005 #include <string>
00006 #include <canopen_master/layer.h>
00007 
00008 namespace canopen {
00009 
00010 class HandleLayerBase: public canopen::Layer{
00011 public:
00012     HandleLayerBase(const std::string &name) : Layer(name) {}
00013 
00014     enum CanSwitchResult{
00015         NotSupported,
00016         NotReadyToSwitch,
00017         ReadyToSwitch,
00018         NoNeedToSwitch
00019     };
00020 
00021     virtual CanSwitchResult canSwitch(const canopen::MotorBase::OperationMode &m) = 0;
00022     virtual bool switchMode(const canopen::MotorBase::OperationMode &m) = 0;
00023 
00024     virtual bool forwardForMode(const canopen::MotorBase::OperationMode &m) = 0;
00025 
00026     virtual void registerHandle(hardware_interface::JointStateInterface &iface) = 0;
00027     virtual hardware_interface::JointHandle* registerHandle(hardware_interface::PositionJointInterface &iface,
00028                                                             const joint_limits_interface::JointLimits &limits,
00029                                                             const joint_limits_interface::SoftJointLimits *soft_limits = 0) = 0;
00030     virtual hardware_interface::JointHandle* registerHandle(hardware_interface::VelocityJointInterface &iface,
00031                                                             const joint_limits_interface::JointLimits &limits,
00032                                                             const joint_limits_interface::SoftJointLimits *soft_limits = 0) = 0;
00033     virtual hardware_interface::JointHandle* registerHandle(hardware_interface::EffortJointInterface &iface,
00034                                                             const joint_limits_interface::JointLimits &limits,
00035                                                             const joint_limits_interface::SoftJointLimits *soft_limits = 0) = 0;
00036 
00037     virtual void enforceLimits(const ros::Duration &period, bool reset) = 0;
00038     virtual void enableLimits(bool enable) = 0;
00039 };
00040 
00041 }  // namespace canopen
00042 
00043 #endif /* CANOPEN_MOTOR_NODE_HANDLE_LAYER_BASE_H_ */


canopen_motor_node
Author(s): Mathias Lüdtke
autogenerated on Sun Sep 3 2017 03:10:55