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

Abstract Class for a CANopen Device Node. More...

#include <cia402_driver.hpp>

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

Public Member Functions

 Cia402Driver (rclcpp::NodeOptions node_options=rclcpp::NodeOptions())
 
virtual bool reset_node_nmt_command ()
 
virtual bool start_node_nmt_command ()
 
virtual bool tpdo_transmit (ros2_canopen::COData &data)
 
virtual bool sdo_write (ros2_canopen::COData &data)
 
virtual bool sdo_read (ros2_canopen::COData &data)
 
void register_nmt_state_cb (std::function< void(canopen::NmtState, uint8_t)> nmt_state_cb)
 
void register_rpdo_cb (std::function< void(COData, uint8_t)> rpdo_cb)
 
double get_speed ()
 
double get_position ()
 
bool set_target (double target)
 
bool init_motor ()
 
bool recover_motor ()
 
bool halt_motor ()
 
bool set_mode_position ()
 
bool set_mode_velocity ()
 
bool set_mode_cyclic_position ()
 
bool set_mode_cyclic_velocity ()
 
bool set_mode_torque ()
 
bool set_mode_interpolated_position ()
 
uint16_t get_mode ()
 
bool set_operation_mode (uint16_t mode)
 
- Public Member Functions inherited from ros2_canopen::CanopenDriver
 CanopenDriver (const rclcpp::NodeOptions &node_options=rclcpp::NodeOptions())
 
virtual void init () override
 Initialise the driver. More...
 
virtual void set_master (std::shared_ptr< lely::ev::Executor > exec, std::shared_ptr< lely::canopen::AsyncMaster > master) override
 Set the master object. More...
 
virtual rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface () override
 Get the node base interface object. More...
 
virtual void shutdown () override
 Shutdown the driver. More...
 
virtual bool is_lifecycle () override
 Check whether this is a LifecycleNode. More...
 
virtual std::shared_ptr< node_interfaces::NodeCanopenDriverInterfaceget_node_canopen_driver_interface ()
 Get the node canopen driver interface object. More...
 

Additional Inherited Members

- Public Attributes inherited from ros2_canopen::CanopenDriver
std::shared_ptr< node_interfaces::NodeCanopenDriverInterfacenode_canopen_driver_
 

Detailed Description

Abstract Class for a CANopen Device Node.

This class provides the base functionality for creating a CANopen device node. It provides callbacks for nmt and rpdo.

Constructor & Destructor Documentation

◆ Cia402Driver()

ros2_canopen::Cia402Driver::Cia402Driver ( rclcpp::NodeOptions  node_options = rclcpp::NodeOptions())

Member Function Documentation

◆ reset_node_nmt_command()

virtual bool ros2_canopen::Cia402Driver::reset_node_nmt_command ( )
inlinevirtual

◆ start_node_nmt_command()

virtual bool ros2_canopen::Cia402Driver::start_node_nmt_command ( )
inlinevirtual

◆ tpdo_transmit()

virtual bool ros2_canopen::Cia402Driver::tpdo_transmit ( ros2_canopen::COData data)
inlinevirtual

◆ sdo_write()

virtual bool ros2_canopen::Cia402Driver::sdo_write ( ros2_canopen::COData data)
inlinevirtual

◆ sdo_read()

virtual bool ros2_canopen::Cia402Driver::sdo_read ( ros2_canopen::COData data)
inlinevirtual

◆ register_nmt_state_cb()

void ros2_canopen::Cia402Driver::register_nmt_state_cb ( std::function< void(canopen::NmtState, uint8_t)>  nmt_state_cb)
inline

◆ register_rpdo_cb()

void ros2_canopen::Cia402Driver::register_rpdo_cb ( std::function< void(COData, uint8_t)>  rpdo_cb)
inline

◆ get_speed()

double ros2_canopen::Cia402Driver::get_speed ( )
inline

◆ get_position()

double ros2_canopen::Cia402Driver::get_position ( )
inline

◆ set_target()

bool ros2_canopen::Cia402Driver::set_target ( double  target)
inline

◆ init_motor()

bool ros2_canopen::Cia402Driver::init_motor ( )
inline

◆ recover_motor()

bool ros2_canopen::Cia402Driver::recover_motor ( )
inline

◆ halt_motor()

bool ros2_canopen::Cia402Driver::halt_motor ( )
inline

◆ set_mode_position()

bool ros2_canopen::Cia402Driver::set_mode_position ( )
inline

◆ set_mode_velocity()

bool ros2_canopen::Cia402Driver::set_mode_velocity ( )
inline

◆ set_mode_cyclic_position()

bool ros2_canopen::Cia402Driver::set_mode_cyclic_position ( )
inline

◆ set_mode_cyclic_velocity()

bool ros2_canopen::Cia402Driver::set_mode_cyclic_velocity ( )
inline

◆ set_mode_torque()

bool ros2_canopen::Cia402Driver::set_mode_torque ( )
inline

◆ set_mode_interpolated_position()

bool ros2_canopen::Cia402Driver::set_mode_interpolated_position ( )
inline

◆ get_mode()

uint16_t ros2_canopen::Cia402Driver::get_mode ( )
inline

◆ set_operation_mode()

bool ros2_canopen::Cia402Driver::set_operation_mode ( uint16_t  mode)
inline

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