ros2_canopen master
C++ ROS CANopen Library
Loading...
Searching...
No Matches
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__402_DRIVER_HPP_
18#define CANOPEN_402_DRIVER__402_DRIVER_HPP_
21
22namespace ros2_canopen
23{
31{
32 std::shared_ptr<node_interfaces::NodeCanopen402Driver<rclcpp::Node>> node_canopen_402_driver_;
33
34public:
35 Cia402Driver(rclcpp::NodeOptions node_options = rclcpp::NodeOptions());
36
38 {
39 return node_canopen_402_driver_->reset_node_nmt_command();
40 }
41
43 {
44 return node_canopen_402_driver_->start_node_nmt_command();
45 }
46
48 {
49 return node_canopen_402_driver_->tpdo_transmit(data);
50 }
51
52 virtual bool sdo_write(ros2_canopen::COData & data)
53 {
54 return node_canopen_402_driver_->sdo_write(data);
55 }
56
57 virtual bool sdo_read(ros2_canopen::COData & data)
58 {
59 return node_canopen_402_driver_->sdo_read(data);
60 }
61
62 void register_nmt_state_cb(std::function<void(canopen::NmtState, uint8_t)> nmt_state_cb)
63 {
64 node_canopen_402_driver_->register_nmt_state_cb(nmt_state_cb);
65 }
66
67 void register_rpdo_cb(std::function<void(COData, uint8_t)> rpdo_cb)
68 {
69 node_canopen_402_driver_->register_rpdo_cb(rpdo_cb);
70 }
71
72 double get_speed() { return node_canopen_402_driver_->get_speed(); }
73
74 double get_position() { return node_canopen_402_driver_->get_position(); }
75
76 bool set_target(double target) { return node_canopen_402_driver_->set_target(target); }
77
78 bool init_motor() { return node_canopen_402_driver_->init_motor(); }
79
80 bool recover_motor() { return node_canopen_402_driver_->recover_motor(); }
81
82 bool halt_motor() { return node_canopen_402_driver_->halt_motor(); }
83
84 uint16_t get_mode() { return node_canopen_402_driver_->get_mode(); }
85
86 bool set_operation_mode(uint16_t mode)
87 {
88 return node_canopen_402_driver_->set_operation_mode(mode);
89 }
90};
91} // namespace ros2_canopen
92
93#endif // CANOPEN_402_DRIVER__CANOPEN_402_DRIVER_HPP_
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
virtual bool reset_node_nmt_command()
Definition cia402_driver.hpp:37
virtual bool sdo_write(ros2_canopen::COData &data)
Definition cia402_driver.hpp:52
uint16_t get_mode()
Definition cia402_driver.hpp:84
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
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 halt_motor()
Definition cia402_driver.hpp:82
bool set_operation_mode(uint16_t mode)
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