17#ifndef CANOPEN_402_DRIVER__CANOPEN_LIFECYCLE_402_DRIVER_HPP_
18#define CANOPEN_402_DRIVER__CANOPEN_LIFECYCLE_402_DRIVER_HPP_
33 std::shared_ptr<node_interfaces::NodeCanopen402Driver<rclcpp_lifecycle::LifecycleNode>>
34 node_canopen_402_driver_;
41 return node_canopen_402_driver_->reset_node_nmt_command();
46 return node_canopen_402_driver_->start_node_nmt_command();
51 return node_canopen_402_driver_->tpdo_transmit(data);
56 return node_canopen_402_driver_->sdo_write(data);
61 return node_canopen_402_driver_->sdo_read(data);
66 node_canopen_402_driver_->register_nmt_state_cb(nmt_state_cb);
71 node_canopen_402_driver_->register_rpdo_cb(rpdo_cb);
74 double get_speed() {
return node_canopen_402_driver_->get_speed(); }
76 double get_position() {
return node_canopen_402_driver_->get_position(); }
78 bool set_target(
double target) {
return node_canopen_402_driver_->set_target(target); }
80 bool init_motor() {
return node_canopen_402_driver_->init_motor(); }
82 bool recover_motor() {
return node_canopen_402_driver_->recover_motor(); }
84 bool halt_motor() {
return node_canopen_402_driver_->halt_motor(); }
86 uint16_t
get_mode() {
return node_canopen_402_driver_->get_mode(); }
90 return node_canopen_402_driver_->set_operation_mode(mode);
Lifecycle Canopen Driver.
Definition driver_node.hpp:190
Lifecycle 402 Driver.
Definition lifecycle_cia402_driver.hpp:32
virtual bool sdo_write(ros2_canopen::COData &data)
Definition lifecycle_cia402_driver.hpp:54
bool halt_motor()
Definition lifecycle_cia402_driver.hpp:84
double get_speed()
Definition lifecycle_cia402_driver.hpp:74
virtual bool tpdo_transmit(ros2_canopen::COData &data)
Definition lifecycle_cia402_driver.hpp:49
bool init_motor()
Definition lifecycle_cia402_driver.hpp:80
bool set_target(double target)
Definition lifecycle_cia402_driver.hpp:78
double get_position()
Definition lifecycle_cia402_driver.hpp:76
virtual bool sdo_read(ros2_canopen::COData &data)
Definition lifecycle_cia402_driver.hpp:59
virtual bool start_node_nmt_command()
Definition lifecycle_cia402_driver.hpp:44
void register_rpdo_cb(std::function< void(COData, uint8_t)> rpdo_cb)
Definition lifecycle_cia402_driver.hpp:69
bool set_operation_mode(uint16_t mode)
Definition lifecycle_cia402_driver.hpp:88
uint16_t get_mode()
Definition lifecycle_cia402_driver.hpp:86
bool recover_motor()
Definition lifecycle_cia402_driver.hpp:82
LifecycleCia402Driver(rclcpp::NodeOptions node_options=rclcpp::NodeOptions())
virtual bool reset_node_nmt_command()
Definition lifecycle_cia402_driver.hpp:39
void register_nmt_state_cb(std::function< void(canopen::NmtState, uint8_t)> nmt_state_cb)
Definition lifecycle_cia402_driver.hpp:64
Definition configuration_manager.hpp:28
Definition exchange.hpp:26