ros2_canopen  master
C++ ROS CANopen Library
default_homing_mode.hpp
Go to the documentation of this file.
1 // Copyright 2023 Christoph Hellmann Santos
2 // Copyright 2014-2022 Authors of ros_canopen
3 //
4 // This program is free software: you can redistribute it and/or modify
5 // it under the terms of the GNU General Public License as published by
6 // the Free Software Foundation, either version 3 of the License, or
7 // (at your option) any later version.
8 //
9 // This program is distributed in the hope that it will be useful,
10 // but WITHOUT ANY WARRANTY; without even the implied warranty of
11 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 // GNU General Public License for more details.
13 //
14 // You should have received a copy of the GNU General Public License
15 // along with this program. If not, see <https://www.gnu.org/licenses/>.
16 //
17 
18 #ifndef DEFAULT_HOMING_MODE_HPP
19 #define DEFAULT_HOMING_MODE_HPP
20 #include <mutex>
22 #include "homing_mode.hpp"
23 
24 namespace ros2_canopen
25 {
26 
28 {
29  const uint16_t index = 0x6098;
30  std::shared_ptr<LelyDriverBridge> driver;
31 
32  std::atomic<bool> execute_;
33 
34  std::mutex mutex_;
35  std::condition_variable cond_;
36  uint16_t status_;
37 
38  enum SW_masks
39  {
40  MASK_Reached = (1 << State402::SW_Target_reached),
41  MASK_Attained = (1 << SW_Attained),
42  MASK_Error = (1 << SW_Error),
43  };
44  bool error(const std::string & msg)
45  {
46  execute_ = false;
47  std::cout << msg << std::endl;
48  return false;
49  }
50 
51 public:
52  DefaultHomingMode(std::shared_ptr<LelyDriverBridge> driver) { this->driver = driver; }
53  virtual bool start();
54  virtual bool read(const uint16_t & sw);
55  virtual bool write(OpModeAccesser & cw);
56 
57  virtual bool executeHoming();
58 };
59 } // namespace ros2_canopen
60 #endif // DEFAULT_HOMING_MODE_HPP
Definition: default_homing_mode.hpp:28
virtual bool read(const uint16_t &sw)
DefaultHomingMode(std::shared_ptr< LelyDriverBridge > driver)
Definition: default_homing_mode.hpp:52
virtual bool write(OpModeAccesser &cw)
Definition: homing_mode.hpp:26
@ SW_Error
Definition: homing_mode.hpp:31
@ SW_Attained
Definition: homing_mode.hpp:30
@ SW_Target_reached
Definition: state.hpp:42
Definition: word_accessor.hpp:27
Definition: configuration_manager.hpp:28