14 #ifndef CANOPEN_BASE_DRIVER__CANOPEN_BASE_DRIVER_HPP_
15 #define CANOPEN_BASE_DRIVER__CANOPEN_BASE_DRIVER_HPP_
30 std::shared_ptr<node_interfaces::NodeCanopenBaseDriver<rclcpp_lifecycle::LifecycleNode>>
31 node_canopen_base_driver_;
38 node_canopen_base_driver_->register_nmt_state_cb(nmt_state_cb);
43 node_canopen_base_driver_->register_rpdo_cb(rpdo_cb);
Lifecycle Base Driver.
Definition: lifecycle_base_driver.hpp:29
LifecycleBaseDriver(rclcpp::NodeOptions node_options=rclcpp::NodeOptions())
void register_rpdo_cb(std::function< void(COData, uint8_t)> rpdo_cb)
Definition: lifecycle_base_driver.hpp:41
void register_nmt_state_cb(std::function< void(canopen::NmtState, uint8_t)> nmt_state_cb)
Definition: lifecycle_base_driver.hpp:36
Lifecycle Canopen Driver.
Definition: driver_node.hpp:190
Definition: configuration_manager.hpp:28
Definition: exchange.hpp:26