KaCanOpen
 All Classes Functions Variables Typedefs Enumerations Pages
pdo.cpp
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 #include <thread>
33 #include <chrono>
34 #include <cstdint>
35 
36 #include "master.h"
37 #include "logger.h"
38 
39 int main() {
40 
41  // Set the name of your CAN bus. "slcan0" is a common bus name
42  // for the first SocketCAN device on a Linux system.
43  const std::string busname = "slcan0";
44 
45  // Set the baudrate of your CAN bus. Most drivers support the values
46  // "1M", "500K", "125K", "100K", "50K", "20K", "10K" and "5K".
47  const std::string baudrate = "500K";
48 
49  PRINT("This example runs a counter completely without SDO transfers.");
50  PRINT("There must be a CiA 401 device which is configured to send 'Read input 8-bit/Digital Inputs 1-8'");
51  PRINT("and 'Read input 8-bit/Digital Inputs 9-16' via TPDO1 and to receive 'Write output 8-bit/Digital Outputs 1-8' via RPDO1.");
52 
53  kaco::Master master;
54  if (!master.start(busname, baudrate)) {
55  PRINT("Starting Master failed.");
56  return EXIT_FAILURE;
57  }
58 
59  std::this_thread::sleep_for(std::chrono::seconds(1));
60 
61  if (master.num_devices()<1) {
62  ERROR("No devices found.");
63  return EXIT_FAILURE;
64  }
65 
66  size_t index;
67  bool found = false;
68  for (size_t i=0; i<master.num_devices(); ++i) {
69  kaco::Device& device = master.get_device(i);
70  device.start();
71  if (device.get_device_profile_number()==401) {
72  index = i;
73  found = true;
74  PRINT("Found CiA 401 device with node ID "<<device.get_node_id());
75  }
76  }
77 
78  if (!found) {
79  ERROR("This example is intended for use with a CiA 401 device but I can't find one.");
80  return EXIT_FAILURE;
81  }
82 
83  kaco::Device& device = master.get_device(index);
84  const auto node_id = device.get_node_id();
85  // device.start(); // already started
86 
88 
89  DUMP(device.get_entry("Manufacturer device name"));
90 
91  // TODO: first configure PDO on device side?
92 
93  device.add_receive_pdo_mapping(0x180+node_id, "Read input 8-bit/Digital Inputs 1-8", 0); // offset 0,
94  device.add_receive_pdo_mapping(0x180+node_id, "Read input 8-bit/Digital Inputs 9-16", 1); // offset 1
95 
96  // transmit PDO on change
97  device.add_transmit_pdo_mapping(0x200+node_id, {{"Write output 8-bit/Digital Outputs 1-8", 0}}); // offset 0
98 
99  // transmit PDO every 500ms
100  //device.add_transmit_pdo_mapping(0x20A, {{"write_output", 0, 0, 0}}, kaco::TransmissionType::PERIODIC, std::chrono::milliseconds(500));
101 
102  for (uint8_t i=0; i<10; ++i) {
103 
104  PRINT("Set output to 0x"<<std::hex<<i<<" (via cache!) and wait 1 second");
105  device.set_entry("Write output 8-bit/Digital Outputs 1-8", i, kaco::WriteAccessMethod::cache);
106  std::this_thread::sleep_for(std::chrono::seconds(1));
107 
108  DUMP_HEX(device.get_entry("Write output 8-bit/Digital Outputs 1-8",kaco::ReadAccessMethod::cache));
109  DUMP_HEX(device.get_entry("Read input 8-bit/Digital Inputs 1-8",kaco::ReadAccessMethod::cache));
110  DUMP_HEX(device.get_entry("Read input 8-bit/Digital Inputs 9-16",kaco::ReadAccessMethod::cache));
111 
112  }
113 
114 }
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
Device & get_device(size_t index) const
Returns a reference to a slave device object.
Definition: master.cpp:84
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 start()
Starts the node via NMT protocol and loads mandatory entries, operations, and constants.
Definition: device.cpp:54
size_t num_devices() const
Returns the number of slave devices in the network.
Definition: master.cpp:80
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
bool start(const std::string busname, const std::string &baudrate)
Starts master and creates Core.
Definition: master.cpp:51
uint16_t get_device_profile_number()
Returns the CiA profile number.
Definition: device.cpp:274
This class represents a master node. It listens for new slaves and provides access to them via get_sl...
Definition: master.h:47
uint8_t get_node_id() const
Returns the node ID of the device.
Definition: device.cpp:74
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 class represents a CanOpen slave device in the network.
Definition: device.h:83
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