ros2_canopen  master
C++ ROS CANopen Library
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Pages
Public Types | Public Member Functions | Protected Member Functions | List of all members
ros2_canopen::MotorBase Class Referenceabstract

Motor Base Class. More...

#include <base.hpp>

Inheritance diagram for ros2_canopen::MotorBase:
Inheritance graph
[legend]

Public Types

enum  OperationMode {
  No_Mode = 0 , Profiled_Position = 1 , Velocity = 2 , Profiled_Velocity = 3 ,
  Profiled_Torque = 4 , Reserved = 5 , Homing = 6 , Interpolated_Position = 7 ,
  Cyclic_Synchronous_Position = 8 , Cyclic_Synchronous_Velocity = 9 , Cyclic_Synchronous_Torque = 10
}
 
typedef std::shared_ptr< MotorBaseMotorBaseSharedPtr
 

Public Member Functions

virtual bool setTarget (double val)=0
 Set target. More...
 
virtual bool enterModeAndWait (uint16_t mode)=0
 Enter Operation Mode. More...
 
virtual bool isModeSupported (uint16_t mode)=0
 Check if Operation Mode is supported. More...
 
virtual uint16_t getMode ()=0
 Get current Mode. More...
 
virtual void registerDefaultModes ()
 Register default Operation Modes. More...
 

Protected Member Functions

 MotorBase ()
 

Detailed Description

Motor Base Class.

Member Typedef Documentation

◆ MotorBaseSharedPtr

Member Enumeration Documentation

◆ OperationMode

Enumerator
No_Mode 
Profiled_Position 
Velocity 
Profiled_Velocity 
Profiled_Torque 
Reserved 
Homing 
Interpolated_Position 
Cyclic_Synchronous_Position 
Cyclic_Synchronous_Velocity 
Cyclic_Synchronous_Torque 

Constructor & Destructor Documentation

◆ MotorBase()

ros2_canopen::MotorBase::MotorBase ( )
inlineprotected

Member Function Documentation

◆ setTarget()

virtual bool ros2_canopen::MotorBase::setTarget ( double  val)
pure virtual

Set target.

Parameters
[in]valTarget value
Returns
true
false

Implemented in ros2_canopen::Motor402.

◆ enterModeAndWait()

virtual bool ros2_canopen::MotorBase::enterModeAndWait ( uint16_t  mode)
pure virtual

Enter Operation Mode.

Parameters
[in]modeTarget Mode
Returns
true
false

Implemented in ros2_canopen::Motor402.

◆ isModeSupported()

virtual bool ros2_canopen::MotorBase::isModeSupported ( uint16_t  mode)
pure virtual

Check if Operation Mode is supported.

Parameters
[in]modeOperation Mode to be checked
Returns
true
false

Implemented in ros2_canopen::Motor402.

◆ getMode()

virtual uint16_t ros2_canopen::MotorBase::getMode ( )
pure virtual

Get current Mode.

Returns
uint16_t

Implemented in ros2_canopen::Motor402.

◆ registerDefaultModes()

virtual void ros2_canopen::MotorBase::registerDefaultModes ( )
inlinevirtual

Register default Operation Modes.

Reimplemented in ros2_canopen::Motor402.


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