ros2_canopen  master
C++ ROS CANopen Library
lifecycle_cia402_driver.hpp
Go to the documentation of this file.
1 // Copyright 2023 Christoph Hellmann Santos
2 //
3 // This program is free software: you can redistribute it and/or modify
4 // it under the terms of the GNU General Public License as published by
5 // the Free Software Foundation, either version 3 of the License, or
6 // (at your option) any later version.
7 //
8 // This program is distributed in the hope that it will be useful,
9 // but WITHOUT ANY WARRANTY; without even the implied warranty of
10 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11 // GNU General Public License for more details.
12 //
13 // You should have received a copy of the GNU General Public License
14 // along with this program. If not, see <https://www.gnu.org/licenses/>.
15 //
16 
17 #ifndef CANOPEN_402_DRIVER__CANOPEN_LIFECYCLE_402_DRIVER_HPP_
18 #define CANOPEN_402_DRIVER__CANOPEN_LIFECYCLE_402_DRIVER_HPP_
19 
22 
23 namespace ros2_canopen
24 {
32 {
33  std::shared_ptr<node_interfaces::NodeCanopen402Driver<rclcpp_lifecycle::LifecycleNode>>
34  node_canopen_402_driver_;
35 
36 public:
37  LifecycleCia402Driver(rclcpp::NodeOptions node_options = rclcpp::NodeOptions());
38 
39  virtual bool reset_node_nmt_command()
40  {
41  return node_canopen_402_driver_->reset_node_nmt_command();
42  }
43 
44  virtual bool start_node_nmt_command()
45  {
46  return node_canopen_402_driver_->start_node_nmt_command();
47  }
48 
49  virtual bool tpdo_transmit(ros2_canopen::COData & data)
50  {
51  return node_canopen_402_driver_->tpdo_transmit(data);
52  }
53 
54  virtual bool sdo_write(ros2_canopen::COData & data)
55  {
56  return node_canopen_402_driver_->sdo_write(data);
57  }
58 
59  virtual bool sdo_read(ros2_canopen::COData & data)
60  {
61  return node_canopen_402_driver_->sdo_read(data);
62  }
63 
64  void register_nmt_state_cb(std::function<void(canopen::NmtState, uint8_t)> nmt_state_cb)
65  {
66  node_canopen_402_driver_->register_nmt_state_cb(nmt_state_cb);
67  }
68 
69  void register_rpdo_cb(std::function<void(COData, uint8_t)> rpdo_cb)
70  {
71  node_canopen_402_driver_->register_rpdo_cb(rpdo_cb);
72  }
73 
74  double get_speed() { return node_canopen_402_driver_->get_speed(); }
75 
76  double get_position() { return node_canopen_402_driver_->get_position(); }
77 
78  bool set_target(double target) { return node_canopen_402_driver_->set_target(target); }
79 
80  bool init_motor() { return node_canopen_402_driver_->init_motor(); }
81 
82  bool recover_motor() { return node_canopen_402_driver_->recover_motor(); }
83 
84  bool halt_motor() { return node_canopen_402_driver_->halt_motor(); }
85 
86  bool set_mode_position() { return node_canopen_402_driver_->set_mode_position(); }
87 
88  bool set_mode_velocity() { return node_canopen_402_driver_->set_mode_velocity(); }
89 
90  bool set_mode_cyclic_position() { return node_canopen_402_driver_->set_mode_cyclic_position(); }
91 
92  bool set_mode_cyclic_velocity() { return node_canopen_402_driver_->set_mode_cyclic_velocity(); }
93 
94  bool set_mode_torque() { return node_canopen_402_driver_->set_mode_torque(); }
95 
97  {
98  return node_canopen_402_driver_->set_mode_interpolated_position();
99  }
100 };
101 } // namespace ros2_canopen
102 
103 #endif // CANOPEN_402_DRIVER__CANOPEN_402_DRIVER_HPP_
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 set_mode_velocity()
Definition: lifecycle_cia402_driver.hpp:88
bool set_mode_cyclic_position()
Definition: lifecycle_cia402_driver.hpp:90
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
bool set_mode_interpolated_position()
Definition: lifecycle_cia402_driver.hpp:96
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
bool set_mode_position()
Definition: lifecycle_cia402_driver.hpp:86
void register_rpdo_cb(std::function< void(COData, uint8_t)> rpdo_cb)
Definition: lifecycle_cia402_driver.hpp:69
bool set_mode_torque()
Definition: lifecycle_cia402_driver.hpp:94
bool set_mode_cyclic_velocity()
Definition: lifecycle_cia402_driver.hpp:92
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