|
ros2_canopen master
C++ ROS CANopen Library
|
Abstract Class for a CANopen Device Node. More...
#include <cia402_driver.hpp>


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 () |
| 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. | |
| virtual void | set_master (std::shared_ptr< lely::ev::Executor > exec, std::shared_ptr< lely::canopen::AsyncMaster > master) override |
| Set the master object. | |
| virtual rclcpp::node_interfaces::NodeBaseInterface::SharedPtr | get_node_base_interface () override |
| Get the node base interface object. | |
| virtual void | shutdown () override |
| Shutdown the driver. | |
| virtual bool | is_lifecycle () override |
| Check whether this is a LifecycleNode. | |
| virtual std::shared_ptr< node_interfaces::NodeCanopenDriverInterface > | get_node_canopen_driver_interface () |
| Get the node canopen driver interface object. | |
Additional Inherited Members | |
Public Attributes inherited from ros2_canopen::CanopenDriver | |
| std::shared_ptr< node_interfaces::NodeCanopenDriverInterface > | node_canopen_driver_ |
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.
| ros2_canopen::Cia402Driver::Cia402Driver | ( | rclcpp::NodeOptions | node_options = rclcpp::NodeOptions() | ) |
|
inlinevirtual |
|
inlinevirtual |
|
inlinevirtual |
|
inlinevirtual |
|
inlinevirtual |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |