ros2_canopen  master
C++ ROS CANopen Library
Public Member Functions | List of all members
ros2_canopen::Motor402 Class Reference

#include <motor.hpp>

Inheritance diagram for ros2_canopen::Motor402:
Inheritance graph
[legend]
Collaboration diagram for ros2_canopen::Motor402:
Collaboration graph
[legend]

Public Member Functions

 Motor402 (std::shared_ptr< LelyDriverBridge > driver, ros2_canopen::State402::InternalState switching_state)
 
virtual bool setTarget (double val)
 Set target. More...
 
virtual bool enterModeAndWait (uint16_t mode)
 Enter Operation Mode. More...
 
virtual bool isModeSupported (uint16_t mode)
 Check if Operation Mode is supported. More...
 
virtual uint16_t getMode ()
 Get current Mode. More...
 
bool readState ()
 
void handleDiag ()
 Updates the device diagnostic information. More...
 
bool handleInit ()
 Initialise the drive. More...
 
void handleRead ()
 Read objects of the drive. More...
 
void handleWrite ()
 Writes objects to the drive. More...
 
bool handleShutdown ()
 Shutdowns the drive. More...
 
bool handleHalt ()
 Executes a quickstop. More...
 
bool handleRecover ()
 Recovers the device from fault. More...
 
template<typename T , typename... Args>
bool registerMode (uint16_t mode, Args &&... args)
 Register a new operation mode for the drive. More...
 
virtual void registerDefaultModes ()
 Tries to register the standard operation modes defined in cia402. More...
 
double get_speed () const
 
double get_position () const
 
void set_diagnostic_status_msgs (std::shared_ptr< DiagnosticsCollector > status, bool enable)
 

Additional Inherited Members

- Public Types inherited from ros2_canopen::MotorBase
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
 
- Protected Member Functions inherited from ros2_canopen::MotorBase
 MotorBase ()
 

Constructor & Destructor Documentation

◆ Motor402()

ros2_canopen::Motor402::Motor402 ( std::shared_ptr< LelyDriverBridge driver,
ros2_canopen::State402::InternalState  switching_state 
)
inline

Member Function Documentation

◆ setTarget()

virtual bool ros2_canopen::Motor402::setTarget ( double  val)
virtual

Set target.

Parameters
[in]valTarget value
Returns
true
false

Implements ros2_canopen::MotorBase.

◆ enterModeAndWait()

virtual bool ros2_canopen::Motor402::enterModeAndWait ( uint16_t  mode)
virtual

Enter Operation Mode.

Parameters
[in]modeTarget Mode
Returns
true
false

Implements ros2_canopen::MotorBase.

◆ isModeSupported()

virtual bool ros2_canopen::Motor402::isModeSupported ( uint16_t  mode)
virtual

Check if Operation Mode is supported.

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

Implements ros2_canopen::MotorBase.

◆ getMode()

virtual uint16_t ros2_canopen::Motor402::getMode ( )
virtual

Get current Mode.

Returns
uint16_t

Implements ros2_canopen::MotorBase.

◆ readState()

bool ros2_canopen::Motor402::readState ( )

◆ handleDiag()

void ros2_canopen::Motor402::handleDiag ( )

Updates the device diagnostic information.

This function updates the diagnostic information of the device by updating the diagnostic status message diagnostic_status_ and publishing it.

◆ handleInit()

bool ros2_canopen::Motor402::handleInit ( )

Initialise the drive.

This function initialises the drive. This means, it first attempts to bring the device to operational state (CIA402) and then executes the chosen homing method.

◆ handleRead()

void ros2_canopen::Motor402::handleRead ( )

Read objects of the drive.

This function should be called regularly. It reads the status word from the device and translates it into the devices state.

◆ handleWrite()

void ros2_canopen::Motor402::handleWrite ( )

Writes objects to the drive.

This function should be called regularly. It writes the new command word to the drive

◆ handleShutdown()

bool ros2_canopen::Motor402::handleShutdown ( )

Shutdowns the drive.

This function shuts down the drive by bringing it into SwitchOn disabled state.

◆ handleHalt()

bool ros2_canopen::Motor402::handleHalt ( )

Executes a quickstop.

The function executes a quickstop.

◆ handleRecover()

bool ros2_canopen::Motor402::handleRecover ( )

Recovers the device from fault.

This function tries to reset faults and put the device back to operational state.

◆ registerMode()

template<typename T , typename... Args>
bool ros2_canopen::Motor402::registerMode ( uint16_t  mode,
Args &&...  args 
)
inline

Register a new operation mode for the drive.

This function will register an operation mode for the drive. It will check if the mode is supported by the drive by reading 0x6508 object.

Template Parameters
T
Args
Parameters
mode
args
Returns
true
false

◆ registerDefaultModes()

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

Tries to register the standard operation modes defined in cia402.

Reimplemented from ros2_canopen::MotorBase.

◆ get_speed()

double ros2_canopen::Motor402::get_speed ( ) const
inline

◆ get_position()

double ros2_canopen::Motor402::get_position ( ) const
inline

◆ set_diagnostic_status_msgs()

void ros2_canopen::Motor402::set_diagnostic_status_msgs ( std::shared_ptr< DiagnosticsCollector status,
bool  enable 
)
inline

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