KaCanOpen
 All Classes Functions Variables Typedefs Enumerations Pages
master.cpp
1 /*
2  * Copyright (c) 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 "canopen_error.h"
38 #include "logger.h"
39 
40 int main() {
41 
42  // ----------- //
43  // Preferences //
44  // ----------- //
45 
46  // The node ID of the slave we want to communicate with.
47  const uint8_t node_id = 2;
48 
49  // Set the name of your CAN bus. "slcan0" is a common bus name
50  // for the first SocketCAN device on a Linux system.
51  const std::string busname = "slcan0";
52 
53  // Set the baudrate of your CAN bus. Most drivers support the values
54  // "1M", "500K", "125K", "100K", "50K", "20K", "10K" and "5K".
55  const std::string baudrate = "500K";
56 
57  // -------------- //
58  // Initialization //
59  // -------------- //
60 
61  std::cout << "This is an example which shows the usage of the Master library." << std::endl;
62 
63  // Create Master (includes Core - accessible via master.core).
64  kaco::Master master;
65 
66  std::cout << "Starting Master (involves starting Core)..." << std::endl;
67  if (!master.start(busname, baudrate)) {
68  std::cout << "Starting Master failed." << std::endl;
69  return EXIT_FAILURE;
70  }
71 
72  bool found_device = false;
73  size_t device_index;
74 
75  while (!found_device) {
76 
77  for (size_t i=0; i<master.num_devices(); ++i) {
78  kaco::Device& device = master.get_device(i);
79  if (device.get_node_id()==node_id) {
80  found_device = true;
81  device_index = i;
82  break;
83  }
84  }
85 
86  std::cout << "Device with ID " << (unsigned) node_id
87  << " has not been found yet. Waiting one more second. Press Ctrl+C abort." << std::endl;
88  std::this_thread::sleep_for(std::chrono::seconds(1));
89 
90  }
91 
92  // ------------ //
93  // Device usage //
94  // ------------ //
95 
96  kaco::Device& device = master.get_device(device_index);
97 
98  std::cout << "Starting device with ID " << (unsigned) node_id << "..." << std::endl;
99  device.start();
100 
101  std::cout << "Loading object dictionary from the library. This can be either a generic CiA-301"
102  << " dictionary, a CiA-profile specific dictionary, or a manufacturer./device-specific dictionary." << std::endl;
103  const std::string loaded_eds_file = device.load_dictionary_from_library();
104  std::cout << "Loaded the following EDS file from the library: " << loaded_eds_file << std::endl;
105 
106  std::cout << "Alternatively, you could load your own EDS file via device.load_dictionary_from_eds(path)." << std::endl;
107  // device.load_dictionary_from_eds("...");
108 
109  std::cout << "The following should work for all CANopen-compliant devices." << std::endl;
110 
111  std::cout << "CiA-profile = " << device.get_device_profile_number() << std::endl;
112 
113  std::cout << "Vendor-ID = " << device.get_entry("Identity object/Vendor-ID") << std::endl;
114 
115  std::cout << "The following works for most CANopen-compliant devices (however, the entries are not mandatory)." << std::endl;
116  try {
117 
118  std::cout << "Manufacturer device name = " << device.get_entry("Manufacturer device name") << std::endl;
119 
120  std::cout << "Manufacturer hardware version = " << device.get_entry("Manufacturer hardware version") << std::endl;
121 
122  std::cout << "Manufacturer software version = " << device.get_entry("Manufacturer software version") << std::endl;
123 
124  } catch (const kaco::canopen_error& error) {
125  std::cout << "Getting manufacturer information failed: " << error.what() << std::endl;
126  }
127 
128  std::cout << "The following should fail on devices which are not CiA-402 motors." << std::endl;
129  try {
130 
131  std::cout << "CiA-402: Set position mode using a built-in constant (see master/src/profiles.cpp)..." << std::endl;
132  device.set_entry("modes_of_operation", device.get_constant("profile_position_mode"));
133 
134  std::cout << "CiA-402: Enable operation using a built-in operation (see master/src/profiles.cpp)..." << std::endl;
135  device.execute("enable_operation");
136 
137  std::cout << "CiA-402: Set target position..." << std::endl;
138  // Type of target position is INT32, so cast accordingly.
139  device.execute("set_target_position", (int32_t) 0);
140 
141  std::cout << "Waiting a second..." << std::endl;
142  std::this_thread::sleep_for(std::chrono::seconds(1));
143 
144  std::cout << "CiA-402: Set target position..." << std::endl;
145  // Type of target position is INT32, so cast accordingly.
146  device.execute("set_target_position", (int32_t) 5000);
147 
148  std::cout << "Waiting a second..." << std::endl;
149  std::this_thread::sleep_for(std::chrono::seconds(1));
150 
151  std::cout << "CiA-402: Set target position..." << std::endl;
152  // Type of target position is INT32, so cast accordingly.
153  device.execute("set_target_position", (int32_t) 10000);
154 
155  } catch (const kaco::canopen_error& error) {
156  std::cout << "CiA-402 failed: " << error.what() << std::endl;
157  }
158 
159  std::cout << "The following should fail on devices which are not CiA-401 I/O devices." << std::endl;
160  try {
161 
162  std::cout << "CiA-401: Set digital output (first byte)..." << std::endl;
163  // Type of this entry is UINT8, so cast accordingly.
164  device.set_entry("Write output 8-bit/Digital Outputs 1-8", (uint8_t) 0xEA);
165 
166  std::cout << "CiA-401: Get digital input (first byte)..." << std::endl;
167  // Correct type casting is also important when reading values.
168  std::cout << "First input byte = 0x" << std::hex << (unsigned) ((uint8_t) device.get_entry("Read input 8 bit/Digital Inputs 1-8")) << std::endl;
169 
170  } catch (const kaco::canopen_error& error) {
171  std::cout << "CiA-401 failed: " << error.what() << std::endl;
172  }
173 
174 }
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
bool start(const std::string busname, const std::string &baudrate)
Starts master and creates Core.
Definition: master.cpp:51
This is the base class of all types of exceptions thrown by the KaCanOpen library. It can be used directly like std::runtime_error if there isn't any more specific error class.
Definition: canopen_error.h:43
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
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 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
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