ros2_canopen  master
C++ ROS CANopen Library
proxy_driver.hpp
Go to the documentation of this file.
1 // Copyright 2022 Christoph Hellmann Santos
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef CANOPEN_PROXY_DRIVER__CANOPEN_PROXY_DRIVER_HPP_
16 #define CANOPEN_PROXY_DRIVER__CANOPEN_PROXY_DRIVER_HPP_
19 
20 namespace ros2_canopen
21 {
29 {
30  std::shared_ptr<node_interfaces::NodeCanopenProxyDriver<rclcpp::Node>> node_canopen_proxy_driver_;
31 
32 public:
33  ProxyDriver(rclcpp::NodeOptions node_options = rclcpp::NodeOptions());
34 
35  virtual bool reset_node_nmt_command()
36  {
37  return node_canopen_proxy_driver_->reset_node_nmt_command();
38  }
39 
40  virtual bool start_node_nmt_command()
41  {
42  return node_canopen_proxy_driver_->start_node_nmt_command();
43  }
44 
45  virtual bool tpdo_transmit(ros2_canopen::COData & data)
46  {
47  return node_canopen_proxy_driver_->tpdo_transmit(data);
48  }
49 
50  virtual bool sdo_write(ros2_canopen::COData & data)
51  {
52  return node_canopen_proxy_driver_->sdo_write(data);
53  }
54 
55  virtual bool sdo_read(ros2_canopen::COData & data)
56  {
57  return node_canopen_proxy_driver_->sdo_read(data);
58  }
59 
60  void register_nmt_state_cb(std::function<void(canopen::NmtState, uint8_t)> nmt_state_cb)
61  {
62  node_canopen_proxy_driver_->register_nmt_state_cb(nmt_state_cb);
63  }
64 
65  void register_rpdo_cb(std::function<void(COData, uint8_t)> rpdo_cb)
66  {
67  node_canopen_proxy_driver_->register_rpdo_cb(rpdo_cb);
68  }
69 };
70 } // namespace ros2_canopen
71 
72 #endif // CANOPEN_PROXY_DRIVER__CANOPEN_PROXY_DRIVER_HPP_
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