37 #include "canopen_error.h"
47 const uint8_t node_id = 2;
51 const std::string busname =
"slcan0";
55 const std::string baudrate =
"500K";
61 std::cout <<
"This is an example which shows the usage of the Master library." << std::endl;
66 std::cout <<
"Starting Master (involves starting Core)..." << std::endl;
67 if (!master.
start(busname, baudrate)) {
68 std::cout <<
"Starting Master failed." << std::endl;
72 bool found_device =
false;
75 while (!found_device) {
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));
98 std::cout <<
"Starting device with ID " << (unsigned) node_id <<
"..." << std::endl;
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;
104 std::cout <<
"Loaded the following EDS file from the library: " << loaded_eds_file << std::endl;
106 std::cout <<
"Alternatively, you could load your own EDS file via device.load_dictionary_from_eds(path)." << std::endl;
109 std::cout <<
"The following should work for all CANopen-compliant devices." << std::endl;
113 std::cout <<
"Vendor-ID = " << device.
get_entry(
"Identity object/Vendor-ID") << std::endl;
115 std::cout <<
"The following works for most CANopen-compliant devices (however, the entries are not mandatory)." << std::endl;
118 std::cout <<
"Manufacturer device name = " << device.
get_entry(
"Manufacturer device name") << std::endl;
120 std::cout <<
"Manufacturer hardware version = " << device.
get_entry(
"Manufacturer hardware version") << std::endl;
122 std::cout <<
"Manufacturer software version = " << device.
get_entry(
"Manufacturer software version") << std::endl;
125 std::cout <<
"Getting manufacturer information failed: " << error.what() << std::endl;
128 std::cout <<
"The following should fail on devices which are not CiA-402 motors." << std::endl;
131 std::cout <<
"CiA-402: Set position mode using a built-in constant (see master/src/profiles.cpp)..." << std::endl;
134 std::cout <<
"CiA-402: Enable operation using a built-in operation (see master/src/profiles.cpp)..." << std::endl;
135 device.
execute(
"enable_operation");
137 std::cout <<
"CiA-402: Set target position..." << std::endl;
139 device.
execute(
"set_target_position", (int32_t) 0);
141 std::cout <<
"Waiting a second..." << std::endl;
142 std::this_thread::sleep_for(std::chrono::seconds(1));
144 std::cout <<
"CiA-402: Set target position..." << std::endl;
146 device.
execute(
"set_target_position", (int32_t) 5000);
148 std::cout <<
"Waiting a second..." << std::endl;
149 std::this_thread::sleep_for(std::chrono::seconds(1));
151 std::cout <<
"CiA-402: Set target position..." << std::endl;
153 device.
execute(
"set_target_position", (int32_t) 10000);
156 std::cout <<
"CiA-402 failed: " << error.what() << std::endl;
159 std::cout <<
"The following should fail on devices which are not CiA-401 I/O devices." << std::endl;
162 std::cout <<
"CiA-401: Set digital output (first byte)..." << std::endl;
164 device.
set_entry(
"Write output 8-bit/Digital Outputs 1-8", (uint8_t) 0xEA);
166 std::cout <<
"CiA-401: Get digital input (first byte)..." << std::endl;
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;
170 } catch (const kaco::canopen_error& error) {
171 std::cout <<
"CiA-401 failed: " << error.what() << std::endl;
Device & get_device(size_t index) const
Returns a reference to a slave device object.
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 ...
void start()
Starts the node via NMT protocol and loads mandatory entries, operations, and constants.
size_t num_devices() const
Returns the number of slave devices in the network.
bool start(const std::string busname, const std::string &baudrate)
Starts master and creates Core.
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.
uint16_t get_device_profile_number()
Returns the CiA profile number.
This class represents a master node. It listens for new slaves and provides access to them via get_sl...
uint8_t get_node_id() const
Returns the node ID of the device.
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(...
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.
This class represents a CanOpen slave device in the network.
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...
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...