KaCanOpen
 All Classes Functions Variables Typedefs Enumerations Pages
device.h
1 /*
2  * Copyright (c) 2015-2016, Thomas Keh
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * 1. Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  *
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in the
13  * documentation and/or other materials provided with the distribution.
14  *
15  * 3. Neither the name of the copyright holder nor the names of its
16  * contributors may be used to endorse or promote products derived from
17  * this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
23  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  */
31 
32 #pragma once
33 
34 #include "core.h"
35 #include "entry.h"
36 #include "types.h"
37 #include "receive_pdo_mapping.h"
38 #include "transmit_pdo_mapping.h"
39 #include "access_method.h"
40 #include "eds_library.h"
41 #include "eds_reader.h"
42 
43 #include <vector>
44 #include <unordered_map>
45 #include <string>
46 #include <chrono>
47 #include <functional>
48 #include <mutex>
49 
50 namespace kaco {
51 
83  class Device {
84 
85  public:
86 
88  using Operation = std::function<Value(Device&,const Value&)>;
89 
93  Device(Core& core, uint8_t node_id);
94 
96  Device(const Device&) = delete;
97 
99  Device(Device&&) = delete;
100 
103  ~Device();
104 
107  uint8_t get_node_id() const;
108 
111 
115  void start();
116 
121  std::string load_dictionary_from_library();
122 
126  void load_dictionary_from_eds(const std::string& path);
127 
130  bool load_operations();
131 
133  void add_operation(const std::string& coperation_name, const Operation& operation);
134 
137  bool load_constants();
138 
140  void add_constant(const std::string& constant_name, const Value& constant);
141 
143 
146 
151  bool has_entry(const std::string& entry_name);
152 
157  bool has_entry(const uint16_t index, const uint8_t subindex = 0);
158 
163  Type get_entry_type(const std::string& entry_name);
164 
169  Type get_entry_type(const uint16_t index, const uint8_t subindex = 0);
170 
179  const Value& get_entry(const std::string& entry_name, const ReadAccessMethod access_method = ReadAccessMethod::use_default);
180 
190  const Value& get_entry(const uint16_t index, const uint8_t subindex = 0, const ReadAccessMethod access_method = ReadAccessMethod::use_default);
191 
201  void set_entry(const std::string& entry_name, const Value& value, const WriteAccessMethod access_method = WriteAccessMethod::use_default);
202 
213  void set_entry(const uint16_t index, const uint8_t subindex, const Value& value, const WriteAccessMethod access_method = WriteAccessMethod::use_default);
214 
222  void add_entry(const uint16_t index, const uint8_t subindex, const std::string& name, const Type type, const AccessType access_type);
223 
227  uint16_t get_device_profile_number();
228 
235  Value execute(const std::string& operation_name, const Value& argument = m_dummy_value);
236 
240  const Value& get_constant(const std::string& constant_name) const;
241 
248  void add_receive_pdo_mapping(uint16_t cob_id, const std::string& entry_name, uint8_t offset);
249 
267  void add_transmit_pdo_mapping(uint16_t cob_id, const std::vector<Mapping>& mappings, TransmissionType transmission_type=TransmissionType::ON_CHANGE, std::chrono::milliseconds repeat_time=std::chrono::milliseconds(0));
268 
270  void print_dictionary() const;
271 
276 
278 
279  private:
280 
283 
292  Value get_entry_via_sdo(uint32_t index, uint8_t subindex, Type type);
293 
302  void set_entry_via_sdo(uint32_t index, uint8_t subindex, const Value& value);
303 
305 
307  void load_cia_dictionary();
308 
309  void pdo_received_callback(const ReceivePDOMapping& mapping, std::vector<uint8_t> data);
310 
311  static const bool debug = false;
312 
313  Core& m_core;
314  uint8_t m_node_id;
315 
316  std::unordered_map<Address, Entry> m_dictionary;
317  std::unordered_map<std::string, Address> m_name_to_address;
318 
319  std::unordered_map<std::string, Operation> m_operations;
320  std::unordered_map<std::string, Value> m_constants;
321  std::forward_list<ReceivePDOMapping> m_receive_pdo_mappings;
322  std::mutex m_receive_pdo_mappings_mutex;
323  std::forward_list<TransmitPDOMapping> m_transmit_pdo_mappings;
324  std::mutex m_transmit_pdo_mappings_mutex;
325  static const Value m_dummy_value;
326  EDSLibrary m_eds_library;
327 
328  };
329 
330 } // end namespace kaco
void print_dictionary() const
Prints the dictionary together with currently cached values to command line.
Definition: device.cpp:461
void add_transmit_pdo_mapping(uint16_t cob_id, const std::vector< Mapping > &mappings, TransmissionType transmission_type=TransmissionType::ON_CHANGE, std::chrono::milliseconds repeat_time=std::chrono::milliseconds(0))
Adds a transmit PDO mapping. This means values from the dictionary cache are sent to the device...
Definition: device.cpp:200
const Value & get_entry(const std::string &entry_name, const ReadAccessMethod access_method=ReadAccessMethod::use_default)
Gets the value of a dictionary entry by name internally. If there is no cached value or the entry is ...
Definition: device.cpp:102
void add_operation(const std::string &coperation_name, const Operation &operation)
Adds a convenience operation.
Definition: device.cpp:420
void add_entry(const uint16_t index, const uint8_t subindex, const std::string &name, const Type type, const AccessType access_type)
Adds an entry to the dictionary. You have to take care that exactly this entry exists on the device f...
Definition: device.cpp:149
void start()
Starts the node via NMT protocol and loads mandatory entries, operations, and constants.
Definition: device.cpp:54
void add_receive_pdo_mapping(uint16_t cob_id, const std::string &entry_name, uint8_t offset)
Adds a receive PDO mapping. This means values sent by the device via PDO are saved into the dictionar...
Definition: device.cpp:163
uint16_t get_device_profile_number()
Returns the CiA profile number.
Definition: device.cpp:274
void add_constant(const std::string &constant_name, const Value &constant)
Adds a constant.
Definition: device.cpp:445
~Device()
Destructor.
Definition: device.cpp:51
This class implements the Core of KaCanOpen It communicates with the CAN driver, sends CAN messages a...
Definition: core.h:59
uint8_t get_node_id() const
Returns the node ID of the device.
Definition: device.cpp:74
Value execute(const std::string &operation_name, const Value &argument=m_dummy_value)
Executes a convenience operation. It must exist due to a previous load_operations() or add_operation(...
Definition: device.cpp:428
std::string load_dictionary_from_library()
Tries to load the most specific EDS file available in KaCanOpen's internal EDS library. This is either device specific, CiA profile specific, or mandatory CiA 301.
Definition: device.cpp:327
This struct represents a mapping from one receive PDO to one dictionary entry. There may be multiple ...
This class represents a CanOpen slave device in the network.
Definition: device.h:83
This class provides access to KaCanOpen's EDS library. It manages device specific as well as generic ...
Definition: eds_library.h:46
bool load_operations()
Loads convenience operations associated with the device profile.
Definition: device.cpp:411
void set_entry(const std::string &entry_name, const Value &value, const WriteAccessMethod access_method=WriteAccessMethod::use_default)
Sets the value of a dictionary entry by name internally. If the entry is configured to send an SDO on...
Definition: device.cpp:123
const Value & get_constant(const std::string &constant_name) const
Returns a constant. It must exist due to a previous load_constants() or add_constant() call...
Definition: device.cpp:453
Type get_entry_type(const std::string &entry_name)
Returns the type of a dictionary entry identified by name as it is defined in the local dictionary...
Definition: device.cpp:87
void read_complete_dictionary()
Fetches all dictionary entries from the device. Afterwards, all values exist in cache and can for exa...
Definition: device.cpp:482
void load_dictionary_from_eds(const std::string &path)
Loads the dictionary from a custom EDS file.
Definition: device.cpp:381
bool has_entry(const std::string &entry_name)
Returns true if the entry is contained in the device dictionary.
Definition: device.cpp:78
Device(Core &core, uint8_t node_id)
Constructor.
Definition: device.cpp:48
std::function< Value(Device &, const Value &)> Operation
Type of a operation. See Profiles::Operation in profiles.h.
Definition: device.h:88
bool load_constants()
Loads constants associated with the device profile.
Definition: device.cpp:436
This class contains a value to be stored in the object dictionary. The value can have one of the type...
Definition: value.h:53