ros2_canopen master
C++ ROS CANopen Library
Loading...
Searching...
No Matches
node_canopen_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 NODE_CANOPEN_PROXY_DRIVER
16#define NODE_CANOPEN_PROXY_DRIVER
17
19namespace ros2_canopen
20{
21namespace node_interfaces
22{
23
24template <class NODETYPE>
26{
27 static_assert(
28 std::is_base_of<rclcpp::Node, NODETYPE>::value ||
29 std::is_base_of<rclcpp_lifecycle::LifecycleNode, NODETYPE>::value,
30 "NODETYPE must derive from rclcpp::Node or rclcpp_lifecycle::LifecycleNode");
31
32protected:
33 rclcpp::Publisher<std_msgs::msg::String>::SharedPtr nmt_state_publisher;
34 rclcpp::Publisher<canopen_interfaces::msg::COData>::SharedPtr rpdo_publisher;
35 rclcpp::Subscription<canopen_interfaces::msg::COData>::SharedPtr tpdo_subscriber;
36 rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr nmt_state_reset_service;
37 rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr nmt_state_start_service;
38 rclcpp::Service<canopen_interfaces::srv::CORead>::SharedPtr sdo_read_service;
39 rclcpp::Service<canopen_interfaces::srv::COWrite>::SharedPtr sdo_write_service;
40
41 std::mutex sdo_mtex;
42
43 virtual void on_nmt(canopen::NmtState nmt_state) override;
44 virtual void on_rpdo(COData data) override;
45 virtual void on_tpdo(const canopen_interfaces::msg::COData::SharedPtr msg);
46 virtual void diagnostic_callback(diagnostic_updater::DiagnosticStatusWrapper & stat) override;
47
49 const std_srvs::srv::Trigger::Request::SharedPtr request,
50 std_srvs::srv::Trigger::Response::SharedPtr response);
51
53 const std_srvs::srv::Trigger::Request::SharedPtr request,
54 std_srvs::srv::Trigger::Response::SharedPtr response);
55
56 void on_sdo_read(
57 const canopen_interfaces::srv::CORead::Request::SharedPtr request,
58 canopen_interfaces::srv::CORead::Response::SharedPtr response);
59
60 void on_sdo_write(
61 const canopen_interfaces::srv::COWrite::Request::SharedPtr request,
62 canopen_interfaces::srv::COWrite::Response::SharedPtr response);
63
64public:
65 NodeCanopenProxyDriver(NODETYPE * node);
66
67 virtual void init(bool called_from_base) override;
68
69 virtual bool reset_node_nmt_command();
70
71 virtual bool start_node_nmt_command();
72
73 virtual bool tpdo_transmit(COData & data);
74
75 virtual bool sdo_write(COData & data);
76
77 virtual bool sdo_read(COData & data);
78};
79} // namespace node_interfaces
80} // namespace ros2_canopen
81
82#endif
Definition node_canopen_base_driver.hpp:34
void init()
Initialise the driver.
Definition node_canopen_driver.hpp:127
Definition node_canopen_proxy_driver.hpp:26
void on_sdo_read(const canopen_interfaces::srv::CORead::Request::SharedPtr request, canopen_interfaces::srv::CORead::Response::SharedPtr response)
Definition node_canopen_proxy_driver_impl.hpp:254
rclcpp::Subscription< canopen_interfaces::msg::COData >::SharedPtr tpdo_subscriber
Definition node_canopen_proxy_driver.hpp:35
rclcpp::Publisher< canopen_interfaces::msg::COData >::SharedPtr rpdo_publisher
Definition node_canopen_proxy_driver.hpp:34
virtual bool sdo_write(COData &data)
Definition node_canopen_proxy_driver_impl.hpp:304
void on_nmt_state_reset(const std_srvs::srv::Trigger::Request::SharedPtr request, std_srvs::srv::Trigger::Response::SharedPtr response)
Definition node_canopen_proxy_driver_impl.hpp:212
rclcpp::Service< canopen_interfaces::srv::CORead >::SharedPtr sdo_read_service
Definition node_canopen_proxy_driver.hpp:38
virtual void diagnostic_callback(diagnostic_updater::DiagnosticStatusWrapper &stat) override
Definition node_canopen_proxy_driver_impl.hpp:337
rclcpp::Service< std_srvs::srv::Trigger >::SharedPtr nmt_state_start_service
Definition node_canopen_proxy_driver.hpp:37
rclcpp::Service< canopen_interfaces::srv::COWrite >::SharedPtr sdo_write_service
Definition node_canopen_proxy_driver.hpp:39
void on_sdo_write(const canopen_interfaces::srv::COWrite::Request::SharedPtr request, canopen_interfaces::srv::COWrite::Response::SharedPtr response)
Definition node_canopen_proxy_driver_impl.hpp:295
void on_nmt_state_start(const std_srvs::srv::Trigger::Request::SharedPtr request, std_srvs::srv::Trigger::Response::SharedPtr response)
Definition node_canopen_proxy_driver_impl.hpp:233
virtual void on_rpdo(COData data) override
Definition node_canopen_proxy_driver_impl.hpp:196
virtual bool reset_node_nmt_command()
Definition node_canopen_proxy_driver_impl.hpp:220
rclcpp::Publisher< std_msgs::msg::String >::SharedPtr nmt_state_publisher
Definition node_canopen_proxy_driver.hpp:33
virtual void on_tpdo(const canopen_interfaces::msg::COData::SharedPtr msg)
Definition node_canopen_proxy_driver_impl.hpp:171
virtual bool tpdo_transmit(COData &data)
Definition node_canopen_proxy_driver_impl.hpp:181
virtual bool start_node_nmt_command()
Definition node_canopen_proxy_driver_impl.hpp:241
virtual void on_nmt(canopen::NmtState nmt_state) override
Definition node_canopen_proxy_driver_impl.hpp:112
virtual bool sdo_read(COData &data)
Definition node_canopen_proxy_driver_impl.hpp:264
rclcpp::Service< std_srvs::srv::Trigger >::SharedPtr nmt_state_reset_service
Definition node_canopen_proxy_driver.hpp:36
std::mutex sdo_mtex
Definition node_canopen_proxy_driver.hpp:41
Definition configuration_manager.hpp:28
Definition exchange.hpp:26