handle_layer_base.h
Go to the documentation of this file.
1 
2 #ifndef CANOPEN_MOTOR_NODE_HANDLE_LAYER_BASE_H_
3 #define CANOPEN_MOTOR_NODE_HANDLE_LAYER_BASE_H_
4 
5 #include <string>
6 #include <canopen_master/layer.h>
7 
8 namespace canopen {
9 
11 public:
12  HandleLayerBase(const std::string &name) : Layer(name) {}
13 
19  };
20 
22  virtual bool switchMode(const canopen::MotorBase::OperationMode &m) = 0;
23 
24  virtual bool forwardForMode(const canopen::MotorBase::OperationMode &m) = 0;
25 
29  const joint_limits_interface::SoftJointLimits *soft_limits = 0) = 0;
32  const joint_limits_interface::SoftJointLimits *soft_limits = 0) = 0;
35  const joint_limits_interface::SoftJointLimits *soft_limits = 0) = 0;
36 
37  virtual void enforceLimits(const ros::Duration &period, bool reset) = 0;
38  virtual void enableLimits(bool enable) = 0;
39 };
41 
42 } // namespace canopen
43 
44 #endif /* CANOPEN_MOTOR_NODE_HANDLE_LAYER_BASE_H_ */
virtual CanSwitchResult canSwitch(const canopen::MotorBase::OperationMode &m)=0
boost::shared_ptr< HandleLayerBase > HandleLayerBaseSharedPtr
virtual void enableLimits(bool enable)=0
virtual void enforceLimits(const ros::Duration &period, bool reset)=0
HandleLayerBase(const std::string &name)
virtual void registerHandle(hardware_interface::JointStateInterface &iface)=0
virtual bool forwardForMode(const canopen::MotorBase::OperationMode &m)=0
const std::string name
virtual bool switchMode(const canopen::MotorBase::OperationMode &m)=0


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