ros2_canopen master
C++ ROS CANopen Library
Loading...
Searching...
No Matches
lifecycle_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_LIFECYCLE_PROXY_DRIVER_HPP_
16#define CANOPEN_PROXY_DRIVER__CANOPEN_LIFECYCLE_PROXY_DRIVER_HPP_
17
20
21namespace ros2_canopen
22{
30{
31 std::shared_ptr<node_interfaces::NodeCanopenProxyDriver<rclcpp_lifecycle::LifecycleNode>>
32 node_canopen_proxy_driver_;
33
34public:
35 LifecycleProxyDriver(rclcpp::NodeOptions node_options = rclcpp::NodeOptions());
37 {
38 return node_canopen_proxy_driver_->reset_node_nmt_command();
39 }
40
42 {
43 return node_canopen_proxy_driver_->start_node_nmt_command();
44 }
45
47 {
48 return node_canopen_proxy_driver_->tpdo_transmit(data);
49 }
50
51 virtual bool sdo_write(ros2_canopen::COData & data)
52 {
53 return node_canopen_proxy_driver_->sdo_write(data);
54 }
55
56 virtual bool sdo_read(ros2_canopen::COData & data)
57 {
58 return node_canopen_proxy_driver_->sdo_read(data);
59 }
60
61 void register_nmt_state_cb(std::function<void(canopen::NmtState, uint8_t)> nmt_state_cb)
62 {
63 node_canopen_proxy_driver_->register_nmt_state_cb(nmt_state_cb);
64 }
65
66 void register_rpdo_cb(std::function<void(COData, uint8_t)> rpdo_cb)
67 {
68 node_canopen_proxy_driver_->register_rpdo_cb(rpdo_cb);
69 }
70};
71} // namespace ros2_canopen
72
73#endif // CANOPEN_PROXY_DRIVER__CANOPEN_LIFECYCLE_PROXY_DRIVER_HPP_
Lifecycle Canopen Driver.
Definition driver_node.hpp:190
Lifecycle Proxy Driver.
Definition lifecycle_proxy_driver.hpp:30
virtual bool reset_node_nmt_command()
Definition lifecycle_proxy_driver.hpp:36
LifecycleProxyDriver(rclcpp::NodeOptions node_options=rclcpp::NodeOptions())
virtual bool tpdo_transmit(ros2_canopen::COData &data)
Definition lifecycle_proxy_driver.hpp:46
virtual bool sdo_read(ros2_canopen::COData &data)
Definition lifecycle_proxy_driver.hpp:56
void register_nmt_state_cb(std::function< void(canopen::NmtState, uint8_t)> nmt_state_cb)
Definition lifecycle_proxy_driver.hpp:61
virtual bool sdo_write(ros2_canopen::COData &data)
Definition lifecycle_proxy_driver.hpp:51
void register_rpdo_cb(std::function< void(COData, uint8_t)> rpdo_cb)
Definition lifecycle_proxy_driver.hpp:66
virtual bool start_node_nmt_command()
Definition lifecycle_proxy_driver.hpp:41
Definition configuration_manager.hpp:28
Definition exchange.hpp:26