This example shows how to use the KaCanOpen Master library. It waits for a device with a specific ID, loads a dictionary from the EDS library and reads and writes various dictionary entries like mandatory and optional CiA-301 entries. If possible, it controls a CiA-402 motor or it handles digital I/Os of a CiA-401 I/O device. Furthermore it shows how to use profile-specific operations and constants.
#include <thread>
#include <chrono>
#include <cstdint>
#include "master.h"
#include "canopen_error.h"
#include "logger.h"
int main() {
const uint8_t node_id = 2;
const std::string busname = "slcan0";
const std::string baudrate = "500K";
std::cout << "This is an example which shows the usage of the Master library." << std::endl;
std::cout << "Starting Master (involves starting Core)..." << std::endl;
if (!master.
start(busname, baudrate)) {
std::cout << "Starting Master failed." << std::endl;
return EXIT_FAILURE;
}
bool found_device = false;
size_t device_index;
while (!found_device) {
found_device = true;
device_index = i;
break;
}
}
std::cout << "Device with ID " << (unsigned) node_id
<< " has not been found yet. Waiting one more second. Press Ctrl+C abort." << std::endl;
std::this_thread::sleep_for(std::chrono::seconds(1));
}
std::cout << "Starting device with ID " << (unsigned) node_id << "..." << std::endl;
std::cout << "Loading object dictionary from the library. This can be either a generic CiA-301"
<< " dictionary, a CiA-profile specific dictionary, or a manufacturer./device-specific dictionary." << std::endl;
std::cout << "Loaded the following EDS file from the library: " << loaded_eds_file << std::endl;
std::cout << "Alternatively, you could load your own EDS file via device.load_dictionary_from_eds(path)." << std::endl;
std::cout << "The following should work for all CANopen-compliant devices." << std::endl;
std::cout <<
"Vendor-ID = " << device.
get_entry(
"Identity object/Vendor-ID") << std::endl;
std::cout << "The following works for most CANopen-compliant devices (however, the entries are not mandatory)." << std::endl;
try {
std::cout <<
"Manufacturer device name = " << device.
get_entry(
"Manufacturer device name") << std::endl;
std::cout <<
"Manufacturer hardware version = " << device.
get_entry(
"Manufacturer hardware version") << std::endl;
std::cout <<
"Manufacturer software version = " << device.
get_entry(
"Manufacturer software version") << std::endl;
std::cout << "Getting manufacturer information failed: " << error.what() << std::endl;
}
std::cout << "The following should fail on devices which are not CiA-402 motors." << std::endl;
try {
std::cout << "CiA-402: Set position mode using a built-in constant (see master/src/profiles.cpp)..." << std::endl;
std::cout << "CiA-402: Enable operation using a built-in operation (see master/src/profiles.cpp)..." << std::endl;
device.
execute(
"enable_operation");
std::cout << "CiA-402: Set target position..." << std::endl;
device.
execute(
"set_target_position", (int32_t) 0);
std::cout << "Waiting a second..." << std::endl;
std::this_thread::sleep_for(std::chrono::seconds(1));
std::cout << "CiA-402: Set target position..." << std::endl;
device.
execute(
"set_target_position", (int32_t) 5000);
std::cout << "Waiting a second..." << std::endl;
std::this_thread::sleep_for(std::chrono::seconds(1));
std::cout << "CiA-402: Set target position..." << std::endl;
device.
execute(
"set_target_position", (int32_t) 10000);
std::cout << "CiA-402 failed: " << error.what() << std::endl;
}
std::cout << "The following should fail on devices which are not CiA-401 I/O devices." << std::endl;
try {
std::cout << "CiA-401: Set digital output (first byte)..." << std::endl;
device.
set_entry(
"Write output 8-bit/Digital Outputs 1-8", (uint8_t) 0xEA);
std::cout << "CiA-401: Get digital input (first byte)..." << std::endl;
std::cout <<
"First input byte = 0x" << std::hex << (unsigned) ((uint8_t) device.
get_entry(
"Read input 8 bit/Digital Inputs 1-8")) << std::endl;
std::cout << "CiA-401 failed: " << error.what() << std::endl;
}
}