Class Cia402Driver
Defined in File cia402_driver.hpp
Inheritance Relationships
Base Type
public ros2_canopen::CanopenDriver
Class Documentation
-
class Cia402Driver : public ros2_canopen::CanopenDriver
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.
Public Functions
-
Cia402Driver(rclcpp::NodeOptions node_options = rclcpp::NodeOptions())
-
inline virtual bool reset_node_nmt_command()
-
inline virtual bool start_node_nmt_command()
-
inline virtual bool tpdo_transmit(ros2_canopen::COData &data)
-
inline virtual bool sdo_write(ros2_canopen::COData &data)
-
inline virtual bool sdo_read(ros2_canopen::COData &data)
-
inline void register_nmt_state_cb(std::function<void(canopen::NmtState, uint8_t)> nmt_state_cb)
-
inline void register_rpdo_cb(std::function<void(COData, uint8_t)> rpdo_cb)
-
inline double get_speed()
-
inline double get_position()
-
inline bool set_target(double target)
-
inline bool init_motor()
-
inline bool recover_motor()
-
inline bool halt_motor()
-
inline uint16_t get_mode()
-
inline bool set_operation_mode(uint16_t mode)
-
Cia402Driver(rclcpp::NodeOptions node_options = rclcpp::NodeOptions())