15 #ifndef CANOPEN_PROXY_DRIVER__CANOPEN_PROXY_DRIVER_HPP_
16 #define CANOPEN_PROXY_DRIVER__CANOPEN_PROXY_DRIVER_HPP_
30 std::shared_ptr<node_interfaces::NodeCanopenProxyDriver<rclcpp::Node>> node_canopen_proxy_driver_;
33 ProxyDriver(rclcpp::NodeOptions node_options = rclcpp::NodeOptions());
37 return node_canopen_proxy_driver_->reset_node_nmt_command();
42 return node_canopen_proxy_driver_->start_node_nmt_command();
47 return node_canopen_proxy_driver_->tpdo_transmit(data);
52 return node_canopen_proxy_driver_->sdo_write(data);
57 return node_canopen_proxy_driver_->sdo_read(data);
62 node_canopen_proxy_driver_->register_nmt_state_cb(nmt_state_cb);
67 node_canopen_proxy_driver_->register_rpdo_cb(rpdo_cb);
Canopen Driver.
Definition: driver_node.hpp:105
Abstract Class for a CANopen Device Node.
Definition: proxy_driver.hpp:29
void register_rpdo_cb(std::function< void(COData, uint8_t)> rpdo_cb)
Definition: proxy_driver.hpp:65
virtual bool start_node_nmt_command()
Definition: proxy_driver.hpp:40
virtual bool tpdo_transmit(ros2_canopen::COData &data)
Definition: proxy_driver.hpp:45
virtual bool reset_node_nmt_command()
Definition: proxy_driver.hpp:35
virtual bool sdo_write(ros2_canopen::COData &data)
Definition: proxy_driver.hpp:50
virtual bool sdo_read(ros2_canopen::COData &data)
Definition: proxy_driver.hpp:55
void register_nmt_state_cb(std::function< void(canopen::NmtState, uint8_t)> nmt_state_cb)
Definition: proxy_driver.hpp:60
ProxyDriver(rclcpp::NodeOptions node_options=rclcpp::NodeOptions())
Definition: configuration_manager.hpp:28
Definition: exchange.hpp:26