ros2_canopen master
C++ ROS CANopen Library
|
#include <motor.hpp>
Public Member Functions | |
Motor402 (std::shared_ptr< LelyDriverBridge > driver, ros2_canopen::State402::InternalState switching_state, int homing_timeout_seconds) | |
virtual bool | setTarget (double val) |
Set target. | |
virtual bool | enterModeAndWait (uint16_t mode) |
Enter Operation Mode. | |
virtual bool | isModeSupported (uint16_t mode) |
Check if Operation Mode is supported. | |
virtual uint16_t | getMode () |
Get current Mode. | |
bool | readState () |
void | handleDiag () |
Updates the device diagnostic information. | |
bool | handleInit () |
Initialise the drive. | |
void | handleRead () |
Read objects of the drive. | |
void | handleWrite () |
Writes objects to the drive. | |
bool | handleShutdown () |
Shutdowns the drive. | |
bool | handleHalt () |
Executes a quickstop. | |
bool | handleRecover () |
Recovers the device from fault. | |
bool | handleEnable () |
Enable the drive. | |
bool | handleDisable () |
Disable the drive. | |
template<typename T , typename... Args> | |
bool | registerMode (uint16_t mode, Args &&... args) |
Register a new operation mode for the drive. | |
virtual void | registerDefaultModes () |
Tries to register the standard operation modes defined in cia402. | |
double | get_speed () const |
double | get_position () const |
void | set_diagnostic_status_msgs (std::shared_ptr< DiagnosticsCollector > status, bool enable) |
Additional Inherited Members | |
![]() | |
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< MotorBase > | MotorBaseSharedPtr |
![]() | |
MotorBase () | |
|
inline |
Enter Operation Mode.
[in] | mode | Target Mode |
Implements ros2_canopen::MotorBase.
Check if Operation Mode is supported.
[in] | mode | Operation Mode to be checked |
Implements ros2_canopen::MotorBase.
bool ros2_canopen::Motor402::readState | ( | ) |
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.
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.
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.
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
bool ros2_canopen::Motor402::handleShutdown | ( | ) |
Shutdowns the drive.
This function shuts down the drive by bringing it into SwitchOn disabled state.
bool ros2_canopen::Motor402::handleHalt | ( | ) |
Executes a quickstop.
The function executes a quickstop.
bool ros2_canopen::Motor402::handleRecover | ( | ) |
Recovers the device from fault.
This function tries to reset faults and put the device back to operational state.
bool ros2_canopen::Motor402::handleEnable | ( | ) |
Enable the drive.
This function enables the drive. This means it attempts to bring the device to operational state (CIA402), and does nothing else.
bool ros2_canopen::Motor402::handleDisable | ( | ) |
Disable the drive.
This function disables the drive. This means it attempts to bring the device to switched on disabled state (CIA402).
|
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.
T | |
Args |
mode | |
args |
Tries to register the standard operation modes defined in cia402.
Reimplemented from ros2_canopen::MotorBase.
|
inline |
|
inline |
|
inline |