17 #ifndef CANOPEN_402_DRIVER__402_DRIVER_HPP_
18 #define CANOPEN_402_DRIVER__402_DRIVER_HPP_
32 std::shared_ptr<node_interfaces::NodeCanopen402Driver<rclcpp::Node>> node_canopen_402_driver_;
35 Cia402Driver(rclcpp::NodeOptions node_options = rclcpp::NodeOptions());
39 return node_canopen_402_driver_->reset_node_nmt_command();
44 return node_canopen_402_driver_->start_node_nmt_command();
49 return node_canopen_402_driver_->tpdo_transmit(data);
54 return node_canopen_402_driver_->sdo_write(data);
59 return node_canopen_402_driver_->sdo_read(data);
64 node_canopen_402_driver_->register_nmt_state_cb(nmt_state_cb);
69 node_canopen_402_driver_->register_rpdo_cb(rpdo_cb);
72 double get_speed() {
return node_canopen_402_driver_->get_speed(); }
74 double get_position() {
return node_canopen_402_driver_->get_position(); }
76 bool set_target(
double target) {
return node_canopen_402_driver_->set_target(target); }
78 bool init_motor() {
return node_canopen_402_driver_->init_motor(); }
80 bool recover_motor() {
return node_canopen_402_driver_->recover_motor(); }
82 bool halt_motor() {
return node_canopen_402_driver_->halt_motor(); }
96 return node_canopen_402_driver_->set_mode_interpolated_position();
99 uint16_t
get_mode() {
return node_canopen_402_driver_->get_mode(); }
103 return node_canopen_402_driver_->set_operation_mode(mode);
Canopen Driver.
Definition: driver_node.hpp:105
Abstract Class for a CANopen Device Node.
Definition: cia402_driver.hpp:31
double get_position()
Definition: cia402_driver.hpp:74
bool set_target(double target)
Definition: cia402_driver.hpp:76
bool recover_motor()
Definition: cia402_driver.hpp:80
bool set_mode_position()
Definition: cia402_driver.hpp:84
virtual bool reset_node_nmt_command()
Definition: cia402_driver.hpp:37
virtual bool sdo_write(ros2_canopen::COData &data)
Definition: cia402_driver.hpp:52
bool set_mode_torque()
Definition: cia402_driver.hpp:92
bool set_mode_interpolated_position()
Definition: cia402_driver.hpp:94
uint16_t get_mode()
Definition: cia402_driver.hpp:99
Cia402Driver(rclcpp::NodeOptions node_options=rclcpp::NodeOptions())
virtual bool tpdo_transmit(ros2_canopen::COData &data)
Definition: cia402_driver.hpp:47
virtual bool sdo_read(ros2_canopen::COData &data)
Definition: cia402_driver.hpp:57
double get_speed()
Definition: cia402_driver.hpp:72
bool set_mode_cyclic_velocity()
Definition: cia402_driver.hpp:90
void register_rpdo_cb(std::function< void(COData, uint8_t)> rpdo_cb)
Definition: cia402_driver.hpp:67
bool init_motor()
Definition: cia402_driver.hpp:78
bool set_mode_cyclic_position()
Definition: cia402_driver.hpp:88
bool halt_motor()
Definition: cia402_driver.hpp:82
bool set_operation_mode(uint16_t mode)
Definition: cia402_driver.hpp:101
bool set_mode_velocity()
Definition: cia402_driver.hpp:86
void register_nmt_state_cb(std::function< void(canopen::NmtState, uint8_t)> nmt_state_cb)
Definition: cia402_driver.hpp:62
virtual bool start_node_nmt_command()
Definition: cia402_driver.hpp:42
Definition: configuration_manager.hpp:28
Definition: exchange.hpp:26